diff --git a/CHANGELOG.md b/CHANGELOG.md index 9119553cdd6..6f096399d2f 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -17,7 +17,10 @@ * Added ad-rss type-stubs for the PythonAPI when building with RSS support * Make TrafficManager PID controller use actual delta times to improve robustness to different fixed_delta_seconds * Fix segfault on LaneCrossingCalculator nullptr access - + * ROS2Native: Extended functionality and performance of ROS2 support + * ROS2Native: Update to fastdds 2.14.6 + * Added Ubuntu 24.04 support + ## CARLA 0.9.16 * Added NVIDIA Cosmos Transfer1 integration diff --git a/Docs/build_linux.md b/Docs/build_linux.md index 63f57b2ee8a..36b2066d9ba 100644 --- a/Docs/build_linux.md +++ b/Docs/build_linux.md @@ -23,7 +23,7 @@ If you come across errors or difficulties then have a look at the **[F.A.Q.](bui ### System requirements -* __Ubuntu 20.04 or 22.04__: The current dev branch of CARLA is tested regularly on Ubuntu 20.04 and Ubuntu 22.04. It may be possible to build CARLA in earlier Ubuntu versions but we recommend a minimum of version 20.04. CARLA has not been tested internally in Ubuntu 24.04, therefore we recommend to stay with a maximum of Ubuntu 22.04. +* __Ubuntu 20.04 or 22.04__: The current dev branch of CARLA is tested regularly on Ubuntu 20.04 and Ubuntu 22.04. It may be possible to build CARLA in earlier Ubuntu versions but we recommend a minimum of version 20.04. CARLA briefly has been tested internally in Ubuntu 24.04, but no regular tests are available yet, therefore we recommend to stay with a maximum of Ubuntu 22.04. * __130 GB disk space__: CARLA will take around 31 GB and Unreal Engine will take around 91 GB so have about 130 GB free to account for both of these plus additional minor software installations. * __A high-performance GPU__: CARLA places a high demand on the GPU, therefore it is recommended to use a minimum of an NVIDIA RTX 2000 series (e.g. 2070) or better with at least 6 Gb of VRAM, preferably 8 Gb or more. * __A high-performance CPU__: CARLA also benefits from a CPU with solid performance. We recommend a minimum of an Intel Core i7 with 4 or more cores (or equivalent). @@ -34,6 +34,17 @@ If you come across errors or difficulties then have a look at the **[F.A.Q.](bui CARLA requires numerous software tools for compilation. Some are built during the CARLA build process itself, such as *Boost.Python*. Others are binaries that should be installed before starting the build (*cmake*, different versions of *Python*, etc.). +#### Ubuntu 24.04 +!!! Note + Experimental + Python: Ubuntu 24.04 is protecting the debian installed python packages. Therefore, either you make use of a virtual environment for the python steps below, or you take the risk and add `--break-system-packages` flag on the install command to allow the behaviour of previous Ubuntu versions. + ROS2: If you want to use the native ROS support, you should be aware, that virtual environments are ignored within the ROS2 environment -- even if the basis of the virtual environment is the system installed python version. In this case you should add `--break-system-packages` and install the packages on user-system level in `~/.local/share`. + If anybody has a better solution and is able to get virtual environments to work with ROS2, please don't hesitate to adapt this note, so everyone can benefit. +```sh +sudo apt-get update +sudo apt-get install build-essential g++-13 cmake ninja-build libvulkan1 python3 python3-dev python3-pip python3-venv autoconf wget curl rsync unzip git git-lfs libpng-dev libtiff5-dev libjpeg-dev +``` + #### Ubuntu 22.04 ```sh sudo apt-get update diff --git a/LibCarla/cmake/fast_dds/CMakeLists.txt b/LibCarla/cmake/fast_dds/CMakeLists.txt index 366549eefaf..79d44a7d13f 100644 --- a/LibCarla/cmake/fast_dds/CMakeLists.txt +++ b/LibCarla/cmake/fast_dds/CMakeLists.txt @@ -1,60 +1,97 @@ 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 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_fastdds_headers} DESTINATION include/carla/ros2) - + 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() + +# Install dependencies for UE4 build 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") +file(GLOB fast_dds_include_dirs "${FASTDDS_INCLUDE_PATH}/*") +foreach(fast_dds_include_dir ${fast_dds_include_dirs}) + install(DIRECTORY "${fast_dds_include_dir}" DESTINATION include) +endforeach() + +# Collect the sources +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_fastdds_sources ${sources}) +endforeach() + +file(GLOB msg_sources "${libcarla_source_path}/carla/ros2/fastdds/*/msg/*.cxx") +list(APPEND libcarla_fastdds_sources ${msg_sources}) + +file(GLOB srv_sources "${libcarla_source_path}/carla/ros2/fastdds/*/srv/*.cxx") +list(APPEND libcarla_fastdds_sources ${srv_sources}) # ============================================================================== # Create targets for debug and release in the same build type. # ============================================================================== +set(libcarla_fastdds_include_directories + # first the fastdds local folder allowing potential overrides of header files + "${libcarla_source_path}/carla/ros2/fastdds" + "${BOOST_INCLUDE_PATH}" + "${RPCLIB_INCLUDE_PATH}" + "${FASTDDS_INCLUDE_PATH}" + "${libcarla_source_path}/carla/ros2" +) if (LIBCARLA_BUILD_RELEASE) - add_library(carla_fastdds STATIC ${libcarla_fastdds_sources}) - - target_compile_options(carla_fastdds PRIVATE -fexceptions) - + add_library(carla_fastdds STATIC + ${libcarla_fastdds_sources} + ) 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}") + ${libcarla_fastdds_include_directories} + ) + target_link_directories(carla_fastdds PRIVATE + ${FASTDDS_LIB_PATH} + ) install(TARGETS carla_fastdds DESTINATION lib) - set_target_properties(carla_fastdds PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_FLAGS_RELEASE}") - + if(NOT WIN32) + set(CMAKE_CXX_FLAGS_RELEASE "-O3 ${CMAKE_CXX_FLAGS_RELEASE}" CACHE STRING "" FORCE) + endif() + set_target_properties(carla_fastdds PROPERTIES COMPILE_FLAGS + "-fexceptions ${CMAKE_CXX_FLAGS_RELEASE}") + target_compile_definitions(carla_fastdds PUBLIC + WITH_ROS2 CARLA_SERVER_BUILD) endif() if (LIBCARLA_BUILD_DEBUG) - - add_library(carla_fastdds_debug STATIC ${libcarla_fastdds_sources}) - - target_compile_options(carla_fastdds_debug PRIVATE -fexceptions) - + add_library(carla_fastdds_debug STATIC + ${libcarla_fastdds_sources} + ) target_include_directories(carla_fastdds_debug SYSTEM PRIVATE - "${BOOST_INCLUDE_PATH}" - "${RPCLIB_INCLUDE_PATH}") + "${libcarla_fastdds_include_directories}" + ) 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) - + set_target_properties(carla_fastdds_debug PROPERTIES COMPILE_FLAGS + "-fexceptions ${CMAKE_CXX_FLAGS_DEBUG}") + target_compile_definitions(carla_fastdds_debug PUBLIC + WITH_ROS2 CARLA_SERVER_BUILD BOOST_ASIO_ENABLE_BUFFER_DEBUGGING) endif() diff --git a/LibCarla/cmake/server/CMakeLists.txt b/LibCarla/cmake/server/CMakeLists.txt index ee8e2c4edfd..72fb893e2c6 100644 --- a/LibCarla/cmake/server/CMakeLists.txt +++ b/LibCarla/cmake/server/CMakeLists.txt @@ -23,8 +23,7 @@ foreach(dir "" "rpc/" "sensor/" "sensor/data/" "sensor/s11n/" "streaming/" "streaming/detail/" "streaming/detail/tcp/" "streaming/low_level/" - "multigpu/" - "ros2/") + "multigpu/") file(GLOB headers "${libcarla_source_path}/carla/${dir}*.h") install(FILES ${headers} DESTINATION include/carla/${dir}) diff --git a/LibCarla/source/carla/Buffer.cpp b/LibCarla/source/carla/Buffer.cpp index acb79114029..e88adada0dd 100644 --- a/LibCarla/source/carla/Buffer.cpp +++ b/LibCarla/source/carla/Buffer.cpp @@ -7,6 +7,7 @@ namespace carla { void Buffer::ReuseThisBuffer() { auto pool = _parent_pool.lock(); if (pool != nullptr) { + log_verbose("Buffer[", static_cast(_data.get()), ":", _size, "]::ReuseThisBuffer() returning buffer to pool:", pool.get()); pool->Push(std::move(*this)); } } diff --git a/LibCarla/source/carla/Buffer.h b/LibCarla/source/carla/Buffer.h index 015ac51139f..3c56f942f23 100644 --- a/LibCarla/source/carla/Buffer.h +++ b/LibCarla/source/carla/Buffer.h @@ -251,9 +251,9 @@ namespace carla { /// allocated. void reset(size_type size) { if (_capacity < size) { - log_debug("allocating buffer of", size, "bytes"); _data = std::make_unique(size); _capacity = size; + log_verbose("Buffer[", static_cast(_data.get()), ":", size, "]::reset() Allocated buffer data (old size: ", _size, ")"); } _size = size; } diff --git a/LibCarla/source/carla/Logging.h b/LibCarla/source/carla/Logging.h index 20ac048fb19..05a9daadfd0 100644 --- a/LibCarla/source/carla/Logging.h +++ b/LibCarla/source/carla/Logging.h @@ -8,6 +8,7 @@ #include "carla/Platform.h" +#define LIBCARLA_LOG_LEVEL_VERBOSE 1 #define LIBCARLA_LOG_LEVEL_DEBUG 10 #define LIBCARLA_LOG_LEVEL_INFO 20 #define LIBCARLA_LOG_LEVEL_WARNING 30 @@ -62,6 +63,21 @@ namespace logging { } // namespace logging +#if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_VERBOSE + + template + static inline void log_verbose(Args && ... args) { + logging::write_to_stream(std::cout, "VERBOSE:", std::forward(args) ..., '\n'); + } + +#else + + template + static inline void log_verbose(Args && ...) {} + +#endif + + #if LIBCARLA_LOG_LEVEL <= LIBCARLA_LOG_LEVEL_DEBUG template diff --git a/LibCarla/source/carla/geom/BoundingBox.h b/LibCarla/source/carla/geom/BoundingBox.h index 6519fe3951e..18f63457000 100644 --- a/LibCarla/source/carla/geom/BoundingBox.h +++ b/LibCarla/source/carla/geom/BoundingBox.h @@ -149,7 +149,7 @@ namespace geom { #endif // LIBCARLA_INCLUDED_FROM_UE4 - MSGPACK_DEFINE_ARRAY(location, extent, rotation, actor_id); + MSGPACK_DEFINE_ARRAY(location, extent, rotation, actor_id) }; inline::std::ostream &operator<<(std::ostream &out, const BoundingBox &box) { diff --git a/LibCarla/source/carla/geom/GeoLocation.h b/LibCarla/source/carla/geom/GeoLocation.h index d51306274c4..a3f5ebd9792 100644 --- a/LibCarla/source/carla/geom/GeoLocation.h +++ b/LibCarla/source/carla/geom/GeoLocation.h @@ -52,7 +52,7 @@ namespace geom { return !(*this == rhs); } - MSGPACK_DEFINE_ARRAY(latitude, longitude, altitude); + MSGPACK_DEFINE_ARRAY(latitude, longitude, altitude) }; inline std::ostream &operator<<(std::ostream &out, const GeoLocation &geo_location) { diff --git a/LibCarla/source/carla/geom/Location.h b/LibCarla/source/carla/geom/Location.h index 4169e97dd4e..b05705094a9 100644 --- a/LibCarla/source/carla/geom/Location.h +++ b/LibCarla/source/carla/geom/Location.h @@ -6,6 +6,9 @@ #pragma once +#include +#include + #include "carla/geom/Vector3D.h" #include "carla/geom/Vector3DInt.h" #include "carla/geom/Math.h" @@ -108,3 +111,13 @@ namespace geom { } // namespace geom } // namespace carla + +namespace std { + +inline std::string to_string(carla::geom::Location const &location) { + std::stringstream str; + str << location; + return str.str(); +} + +} // namespace std \ No newline at end of file diff --git a/LibCarla/source/carla/geom/Quaternion.h b/LibCarla/source/carla/geom/Quaternion.h index 343fc7fd4a5..9842d357d4d 100644 --- a/LibCarla/source/carla/geom/Quaternion.h +++ b/LibCarla/source/carla/geom/Quaternion.h @@ -8,6 +8,7 @@ #include #include +#include #include "carla/MsgPack.h" #include "carla/geom/Math.h" @@ -375,3 +376,13 @@ inline std::ostream &operator<<(std::ostream &out, const Quaternion &quaternion) } // namespace geom } // namespace carla + +namespace std { + +inline std::string to_string(carla::geom::Quaternion const &quaternion) { + std::stringstream str; + str << quaternion; + return str.str(); +} + +} // namespace std \ No newline at end of file diff --git a/LibCarla/source/carla/geom/Rotation.h b/LibCarla/source/carla/geom/Rotation.h index 4650130b1f6..2e00e10096a 100644 --- a/LibCarla/source/carla/geom/Rotation.h +++ b/LibCarla/source/carla/geom/Rotation.h @@ -7,6 +7,7 @@ #pragma once #include +#include #include "carla/MsgPack.h" #include "carla/geom/Math.h" @@ -38,7 +39,7 @@ namespace geom { float roll = 0.0f; - MSGPACK_DEFINE_ARRAY(pitch, yaw, roll); + MSGPACK_DEFINE_ARRAY(pitch, yaw, roll) // ========================================================================= // -- Constructors --------------------------------------------------------- @@ -168,4 +169,14 @@ namespace geom { } } // namespace geom -} // namespace carla \ No newline at end of file +} // namespace carla + +namespace std { + +inline std::string to_string(carla::geom::Rotation const &rotator) { + std::stringstream str; + str << rotator; + return str.str(); +} + +} // namespace std diff --git a/LibCarla/source/carla/geom/Transform.h b/LibCarla/source/carla/geom/Transform.h index a13e31f6e7c..31f37947387 100644 --- a/LibCarla/source/carla/geom/Transform.h +++ b/LibCarla/source/carla/geom/Transform.h @@ -7,6 +7,7 @@ #pragma once #include +#include #include "carla/MsgPack.h" #include "carla/geom/Location.h" @@ -34,7 +35,7 @@ namespace geom { Rotation rotation; - MSGPACK_DEFINE_ARRAY(location, rotation); + MSGPACK_DEFINE_ARRAY(location, rotation) // ========================================================================= // -- Constructors --------------------------------------------------------- @@ -147,3 +148,14 @@ namespace geom { } // namespace geom } // namespace carla + + +namespace std { + +inline std::string to_string(carla::geom::Transform const &transform) { + std::stringstream str; + str << transform; + return str.str(); +} + +} // namespace std \ No newline at end of file diff --git a/LibCarla/source/carla/image/ColorConverter.h b/LibCarla/source/carla/image/ColorConverter.h index 4c616b2cb51..0c9d6b0aa1c 100644 --- a/LibCarla/source/carla/image/ColorConverter.h +++ b/LibCarla/source/carla/image/ColorConverter.h @@ -32,10 +32,10 @@ namespace image { static_assert( sizeof(typename color_space_type::type) == sizeof(uint8_t), "Invalid pixel type."); - const float depth = + const float depth = static_cast( get_color(src, red_t()) + (get_color(src, green_t()) * 256) + - (get_color(src, blue_t()) * 256 * 256); + (get_color(src, blue_t()) * 256 * 256)); const float normalized = depth / static_cast(256 * 256 * 256 - 1); color_convert(gray32fc_pixel_t{normalized}, dst); } diff --git a/LibCarla/source/carla/ros2/ROS2.cpp b/LibCarla/source/carla/ros2/ROS2.cpp index 184da86f326..0a0908479f8 100644 --- a/LibCarla/source/carla/ros2/ROS2.cpp +++ b/LibCarla/source/carla/ros2/ROS2.cpp @@ -9,447 +9,223 @@ #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/impl/DdsDomainParticipantImpl.h" +#include "carla/ros2/publishers/UeWorldPublisher.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 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; -} +// 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::Enable(carla::rpc::RpcServerInterface *carla_server, + carla::streaming::detail::stream_id_type const world_observer_stream_id, + ROS2TopicVisibilityDefaultMode topic_visibility_default_mode) { + _enabled = true; + _topic_visibility_default_mode = topic_visibility_default_mode; + _carla_server = carla_server; + _name_registry = std::make_shared(); + _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("/", _topic_visibility_default_mode); + _world_observer_sensor_actor_definition = std::make_shared( + *world_observer_actor_definition, + carla::ros2::types::PublisherSensorType::WorldObserver, + world_observer_stream_id); + log_info("ROS2 enabled"); + + // initialize the load map service immediately since that + // has to stay alive during a map reload to send the response back to the client + _load_map_service = std::make_shared( + *_carla_server, carla::ros2::types::ActorNameDefinition::CreateFromRoleName("load_map")); + _load_map_service->Init(_domain_participant_impl); +} + +void ROS2::NotifyInitGame() { + log_info("ROS2 NotifyInitGame"); + + // The world is crucial and has to be instanciated immediately + _world_publisher = std::make_shared(*_carla_server, _name_registry, _world_observer_sensor_actor_definition); + if (!_world_publisher->Init(_domain_participant_impl)) { + log_error("ROS2::NotifyInitGame[", std::to_string(*_world_observer_sensor_actor_definition), + "]: Failed to init publisher"); + } else { + log_debug("ROS2::NotifyInitGame[", std::to_string(*_world_observer_sensor_actor_definition), + "]: Publisher initialized"); + } -void ROS2::SetFrame(uint64_t frame) { - _frame = frame; + ProcessDataFromUeSensorPreAction(); +} - for (auto& element : _subscribers) { - auto actor = element.first; - auto subscriber = element.second; - auto callback = _actor_callbacks.find(actor)->second; +void ROS2::NotifyBeginEpisode() { + log_info("ROS2 NotifyBeginEpisode"); - subscriber->ProcessMessages(callback); - } -} + 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); -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(); -} + 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); -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}); -} + 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); -void ROS2::UnregisterActor(void *actor) { - _registered_actors.erase(actor); - _frame_ids.erase(actor); - _actor_parent_map.erase(actor); - _tfs.erase(actor); -} + 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); -void ROS2::RegisterActorParent(void *actor, void *parent) { - _actor_parent_map.insert({actor, parent}); + 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); + + // inform load map service about new episode to trigger pending map change if there is any + _load_map_service->NotifyBeginEpisode(); + _services.push_back(_load_map_service); } -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::NotifyEndEpisode() { + log_info("ROS2 NotifyEndEpisode"); + _services.clear(); + _name_registry->Clear(); + _world_publisher->Cleanup(); } -void ROS2::UnregisterSensor(void *actor) { - UnregisterActor(actor); - _publishers.erase(actor); +void ROS2::NotifyEndGame() { + log_info("ROS2 NotifyEndGame"); + NotifyEndEpisode(); + _world_publisher.reset(); } -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::Disable() { + NotifyEndEpisode(); + NotifyEndGame(); + _load_map_service.reset(); + _world_observer_sensor_actor_definition.reset(); + _domain_participant_impl.reset(); + _name_registry.reset(); + _enabled = false; + log_info("ROS2 disabled"); } -void ROS2::UnregisterVehicle(void *actor) { - UnregisterActor(actor); - _actor_callbacks.erase(actor); - _subscribers.erase(actor); +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_debug("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::GetActorRosName(void *actor) { - auto it = _registered_actors.find(actor); - return it != _registered_actors.end() ? it->second : ""; +void ROS2::AddWalkerUe(std::shared_ptr walker_actor_definition, + carla::ros2::types::WalkerControlCallback walker_control_callback) { + log_debug("ROS2::AddWalkerUe(", std::to_string(*walker_actor_definition), ")"); + _world_publisher->AddWalkerUe(walker_actor_definition, walker_control_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::AddTrafficLightUe( + std::shared_ptr traffic_light_actor_definition) { + log_debug("ROS2::AddTrafficLightUe(", std::to_string(*traffic_light_actor_definition), ")"); + _world_publisher->AddTrafficLightUe(traffic_light_actor_definition); } -std::string ROS2::GetFrameId(void *actor) { - auto it = _frame_ids.find(actor); - return it != _frame_ids.end() ? it->second : ""; +void ROS2::AddTrafficSignUe( + std::shared_ptr traffic_sign_actor_definition) { + log_debug("ROS2::AddTrafficSignUe(", std::to_string(*traffic_sign_actor_definition), ")"); + _world_publisher->AddTrafficSignUe(traffic_sign_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::AddSensorUe(std::shared_ptr sensor_actor_definition, + carla::ros2::types::ActorSetTransformCallback actor_set_transform_callback) { + log_debug("ROS2::AddSensorUe(", std::to_string(*sensor_actor_definition), ")"); + _world_publisher->AddSensorUe(sensor_actor_definition, actor_set_transform_callback); } -std::shared_ptr ROS2::GetOrCreateTransformPublisher(void *actor) { - - auto it = _tfs.find(actor); - if (it == _tfs.end() || it->second == false) { - return nullptr; - } - - // 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; +void ROS2::AddV2XCustomSensorUe(std::shared_ptr sensor_actor_definition, + carla::ros2::types::V2XCustomSendCallback v2x_custom_send_callback) { + log_debug("ROS2::AddV2XCustomSensorUe(", std::to_string(*sensor_actor_definition), ")"); + _world_publisher->AddV2XCustomSensorUe(sensor_actor_definition, v2x_custom_send_callback); } -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; - } - - 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)); - } - return nullptr; +void ROS2::AttachActors(ActorId const child, ActorId const parent) { + log_debug("ROS2::AttachActors[", child, "]: parent=", parent); + _world_publisher->AttachActors(child, parent); } -void ROS2::ProcessDataFromCamera( - uint64_t sensor_type, - const carla::geom::Transform sensor_transform, - const carla::SharedBufferView buffer, - void *actor) { - - auto base_publisher = GetOrCreateSensor(static_cast(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, reinterpret_cast(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::RemoveActor(ActorId const actor) { + _world_publisher->RemoveActor(actor); } -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::ProcessMessages() { + for (auto service : _services) { + service->CheckRequest(); } + _world_publisher->ProcessMessages(); } -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::ProcessDataFromUeSensorPreAction() { + _world_publisher->UpdateSensorDataPreAction(); } -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, static_cast(im_height), static_cast(im_width), header->fov_angle, true); - sensor_publisher->WriteImage(_seconds, _nanoseconds, static_cast(elements), header->height, header->width, reinterpret_cast(buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset)); - sensor_publisher->WritePointCloud(_seconds, _nanoseconds, 1, static_cast(elements), const_cast(reinterpret_cast(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::ProcessDataFromUeSensor(carla::streaming::detail::stream_id_type const stream_id, + std::shared_ptr message) { + _world_publisher->ProcessDataFromUeSensor(stream_id, message); } -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. - const uint32_t width = static_cast(data._points.size() / 4); - const uint32_t height = 1; - sensor_publisher->WritePointCloud(_seconds, _nanoseconds, height, width, reinterpret_cast(data._points.data())); - sensor_publisher->Publish(); - - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); - } +void ROS2::ProcessDataFromUeSensorPostAction() { + _world_publisher->UpdateSensorDataPostAction(); } -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); - - const uint32_t width = static_cast(data._ser_points.size()); - const uint32_t height = 1; - sensor_publisher->WritePointCloud(_seconds, _nanoseconds, height, width, reinterpret_cast(data._ser_points.data())); - sensor_publisher->Publish(); - - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); - } +void ROS2::EnableForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { + _world_publisher->enable_for_ros(stream_actor_id.actor_id); } -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); - - const uint32_t width = static_cast(data.GetDetectionCount()); - const uint32_t height = 1; - sensor_publisher->WritePointCloud(_seconds, _nanoseconds, height, width, reinterpret_cast(const_cast(data._detections.data()))); - sensor_publisher->Publish(); - - 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) { + _world_publisher->disable_for_ros(stream_actor_id.actor_id); } -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); +bool ROS2::IsEnabledForROS(carla::streaming::detail::stream_actor_id_type stream_actor_id) { + return _world_publisher->is_enabled_for_ros(stream_actor_id.actor_id); } -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(); - - if (transform_publisher) { - transform_publisher->Write(_seconds, _nanoseconds, GetParentFrameId(actor), GetFrameId(actor), sensor_transform); - transform_publisher->Publish(); - } +uint64_t ROS2::CurrentFrame() const { + return (_world_publisher != nullptr) ? _world_publisher->CurrentFrame() : 0u; } -void ROS2::Shutdown() { - _publishers.clear(); - _subscribers.clear(); - - _tf_publishers.clear(); - - _clock_publisher.reset(); - - _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..d3c3a561f7e 100644 --- a/LibCarla/source/carla/ros2/ROS2.h +++ b/LibCarla/source/carla/ros2/ROS2.h @@ -6,162 +6,116 @@ #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/ROS2TopicVisibilityDefaultMode.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 sensor { - namespace data { - struct DVSEvent; - class LidarData; - class SemanticLidarData; - class RadarData; - } - } -} 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); +class DdsDomainParticipantImpl; +class UePublisherBase; +class TransformPublisher; +class CarlaActorListPublisher; +class UeWorldPublisher; +class ServiceInterface; +class LoadMapService; - // sigleton - ROS2() {}; - - static std::shared_ptr _instance; +class ROS2 { +public: + // deleting copy constructor for singleton + ROS2(const ROS2& obj) = delete; + ~ROS2() = default; - bool _enabled { false }; - uint64_t _frame { 0 }; - int32_t _seconds { 0 }; - uint32_t _nanoseconds { 0 }; + static std::shared_ptr GetInstance(); - std::shared_ptr _clock_publisher; - // actor->parent relationship - std::unordered_map _actor_parent_map; + void Enable(carla::rpc::RpcServerInterface* carla_server, + carla::streaming::detail::stream_id_type const world_observer_stream_id, + ROS2TopicVisibilityDefaultMode topic_visibility_default_mode); + bool IsEnabled() const { + return _enabled; + } + ROS2TopicVisibilityDefaultMode 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); + void AddSensorUe(std::shared_ptr sensor_actor_definition, + carla::ros2::types::ActorSetTransformCallback actor_set_transform_callback = nullptr); + void 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; + } - std::unordered_map _registered_actors; - std::unordered_map _frame_ids; +private: + bool _enabled{false}; + ROS2TopicVisibilityDefaultMode _topic_visibility_default_mode{ROS2TopicVisibilityDefaultMode::eOn}; + carla::rpc::RpcServerInterface* _carla_server{nullptr}; + std::shared_ptr _name_registry{nullptr}; + std::shared_ptr _domain_participant_impl; + std::shared_ptr _world_observer_sensor_actor_definition; - std::unordered_map> _publishers; - std::unordered_multimap> _subscribers; - std::unordered_map _actor_callbacks; + std::shared_ptr _world_publisher; + std::list> _services; + std::shared_ptr _load_map_service; - std::unordered_map _tfs; - std::unordered_map> _tf_publishers; + // sigleton + 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..b530e008fae --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2NameRecord.cpp @@ -0,0 +1,51 @@ +// 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 "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); +} + +carla::streaming::detail::actor_id_type ROS2NameRecord::get_actor_id() const { + return _actor_name_definition->id; +} + +carla::streaming::detail::actor_id_type ROS2NameRecord::get_parent_actor_id() const { + return ROS2::GetInstance()->GetNameRegistry()->ParentActorId(_actor_name_definition->id); +} + +} // 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..0570ac3696f --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2NameRecord.h @@ -0,0 +1,43 @@ +// 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/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; + + carla::streaming::detail::actor_id_type get_actor_id() const; + + carla::streaming::detail::actor_id_type get_parent_actor_id() 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..5b629c4f23d --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2NameRegistry.cpp @@ -0,0 +1,349 @@ +// 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 + +#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); + KeyType key(record); + auto insert_result = record_set.insert(key); + insert_result.first->_number_of_register_calls++; + if (insert_result.second) { + log_debug("ROS2NameRegistry::RegisterRecord: ", + std::to_string(*insert_result.first->_actor_name_definition)); + } +} + +void ROS2NameRegistry::UnregisterRecord(ROS2NameRecord const* record) { + std::lock_guard lock(access_mutex); + KeyType key(record); + auto find_result = record_set.find(key); + if ( find_result != record_set.end() ) { + find_result->_number_of_register_calls--; + if ( find_result->_number_of_register_calls == 0u) { + log_debug("ROS2NameRegistry::UnregisterRecord: ", + std::to_string(*find_result->_actor_name_definition)); + + auto const actor_id = find_result->_actor_name_definition->id; + record_set.erase(find_result); + topic_and_frame_map.erase(key); + + 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; + } + } + } + } +} + +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(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; +} + +std::string ROS2NameRegistry::FrameId(carla::streaming::detail::actor_id_type const actor_id) +{ + std::lock_guard lock(access_mutex); + std::string result_topic_name = ""; + for (auto& record : record_set) { + if (record._actor_name_definition->id == actor_id) { + auto const frame_id = GetTopicAndFrameLocked(record)._frame_id; + return frame_id; + } + } + return ""; +} + +ROS2NameRegistry::TopicAndFrame const& ROS2NameRegistry::GetParentTopicAndFrameLocked( + KeyType 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._actor_name_definition), + std::to_string(*parent_iter->first._actor_name_definition), + " This is not an expected configuration. Cannot decide what to return. 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 + KeyType parent_key(nullptr); + for (auto& record : record_set) { + if (record._actor_name_definition->id == parent_actor_id) { + if (parent_key._actor_name_definition != 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_key._actor_name_definition), + " This is not an expected configuration. Cannot decide what to create. Ignore parent"); + return g_empty_topic_and_frame; + } else { + parent_key = record; + } + } + } + if (parent_key._actor_name_definition != nullptr) { + log_debug("ROS2NameRegistry::GetParentTopicAndFrameLocked: child ", + std::to_string(*child_record._actor_name_definition) ," found parent ", + std::to_string(*parent_key._actor_name_definition)); + return CreateTopicAndFrameLocked(parent_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) { + (void)CreateTopicAndFrameLocked(record); + } + } +} + +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._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); + } + + 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"; // maybe not a good idea to break the interface of existing ROS-clients + } else if (walker_actor_definition != nullptr) { + type = ""; //"walkers"; // maybe not a good idea to break the interface of existing ROS-clients + } 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"; // maybe not a good idea to break the interface of existing ROS-clients + } else { + type = ""; //"world"; // maybe not a good idea to break the interface of existing ROS-clients + } + // 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), actor_definition->frame_id); + } else { + topic_and_frame = ExpandTopicName(topic_and_frame, actor_definition->ros_name, actor_definition->frame_id); + } + // 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_topic, std::string const& postfix_frame) { + auto postfix_topic_adapted = postfix_topic; + while (postfix_topic_adapted.front() == '/') { + postfix_topic_adapted.erase(postfix_topic_adapted.begin()); + } + std::string postfix_frame_adapted; + if ( postfix_frame.empty()) { + postfix_frame_adapted = postfix_topic_adapted; + } + else { + while (postfix_frame_adapted.front() == '/') { + postfix_frame_adapted.erase(postfix_frame_adapted.begin()); + } + } + TopicAndFrame expanded_topic_and_frame = topic_and_frame; + if ( !postfix_frame_adapted.empty() ) { + 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); + } + expanded_topic_and_frame._frame_id += postfix_frame_adapted; + } + if ( !postfix_topic_adapted.empty() ) { + if (expanded_topic_and_frame._topic_name.back() != '/') { + expanded_topic_and_frame._topic_name.push_back('/'); + } + expanded_topic_and_frame._topic_name += postfix_topic_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..f890e0ccd75 --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2NameRegistry.h @@ -0,0 +1,137 @@ +// 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 "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); + + /*! + @brief returns the FrameId for this actor_id + */ + std::string FrameId(carla::streaming::detail::actor_id_type const actor_id); + + std::string FrameId(ROS2NameRecord const* record) { + std::lock_guard lock(access_mutex); + std::string frame_id = GetTopicAndFrameLocked(record)._frame_id; + if (frame_id.empty()) { + frame_id = "map"; + } + return 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); + // per default frame and topic postfix are considered to be equal + TopicAndFrame ExpandTopicName(TopicAndFrame const& topic_and_frame, std::string const& postfix_topic, std::string const& postfix_frame=""); + + struct KeyType { + explicit KeyType(ROS2NameRecord const* record) : + _actor_name_definition(record->_actor_name_definition) {} + + bool operator<(const KeyType& other) const { + // the actor name definition shared pointer is the differentiating piece + return _actor_name_definition < other._actor_name_definition; + } + carla::streaming::detail::actor_id_type actor_id()const { return _actor_name_definition->id; } + + std::shared_ptr _actor_name_definition; + mutable uint32_t _number_of_register_calls{0u}; + }; + + // locked operations + TopicAndFrame const& GetTopicAndFrameLocked(KeyType const& key); + TopicAndFrame const& GetParentTopicAndFrameLocked(KeyType const& key); + + TopicAndFrame const& GetTopicAndFrameLocked(ROS2NameRecord const* record){ + return GetTopicAndFrameLocked(KeyType(record)); + } + TopicAndFrame const& GetParentTopicAndFrameLocked(ROS2NameRecord const* record) { + return GetParentTopicAndFrameLocked(KeyType(record)); + } + + 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; + std::set missing_parents; +}; + +} // 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..84be01b63bc --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2QoS.h @@ -0,0 +1,81 @@ +// 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 { + +/* + * Struct providing the most prominent ROS2 ROS2QoS parameters + */ +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; + } + + ROS2QoS &force_synchronous_writer(bool force_synchronous_writer = true) { + _force_synchronous_writer = force_synchronous_writer; + 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; + + bool _force_synchronous_writer = false; +}; + +/** + * Default ROS2 QoS parameters for subscribers: best_effort, volatile, keep_last with history size 10. + * Connects to any publisher configuration. + */ +static constexpr ROS2QoS DEFAULT_SUBSCRIBER_QOS{ROS2QoS::Reliability::BEST_EFFORT, ROS2QoS::Durability::VOLATILE, + ROS2QoS::History::KEEP_LAST, 10}; + +/** + * Default ROS2 QoS parameters for publishers: reliable, transient_local, keep_last with history size 10. + * Connects to any subscriber configuration. + * Note history size>1 are only meaningful for transient_local durability. + * Note history size=10 is a good compromise between memory consumption and data loss in case of high system load or late subscribers. + * Since CARLA subscribers might want to record all simulation frames, we use a larger history depth here. + */ +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..f52cdbe9d23 --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2Session.cpp @@ -0,0 +1,34 @@ +// 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 "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..693ab9ff804 --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2Session.h @@ -0,0 +1,36 @@ +// 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/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/ROS2TopicVisibilityDefaultMode.h b/LibCarla/source/carla/ros2/ROS2TopicVisibilityDefaultMode.h new file mode 100644 index 00000000000..b7953933667 --- /dev/null +++ b/LibCarla/source/carla/ros2/ROS2TopicVisibilityDefaultMode.h @@ -0,0 +1,19 @@ +// 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 + +namespace carla { +namespace ros2 { + +enum class ROS2TopicVisibilityDefaultMode { + eOn, + eOff +}; + +} // 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..35ed0ba8d15 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/README.md @@ -0,0 +1,28 @@ +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 + - clean the idl files by calling the clean_idl_file.bash script on the files e.g. + ```find install/carla_msgs -name "*.idl" -exec clean_idl_file.bash {} \;``` + - the cleaning adds "#pragma once" directive if not yet present to prevent from multiple including the files + * 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 + cd /opt/ros//share + Fast-DDS-GEN/scripts/fastddsgen -d /output-code -I /opt/ros//share/ -typeros2 ackermann_msgs/msg/AckermannDrive.idl nav_msgs/msg/Odometry.idl std_msgs/msg/Float32.idl sensor_msgs/msg/NavSatFix.idl sensor_msgs/msg/Imu.idl sensor_msgs/msg/PointCloud2.idl sensor_msgs/msg/Image.idl sensor_msgs/msg/CameraInfo.idl tf2_msgs/msg/TFMessage.idl derived_object_msgs/msg/ObjectWithCovarianceArray.idl rosgraph_msgs/msg/Clock.idl derived_object_msgs/msg/ObjectArray.idl rosgraph_msgs/msg/Clock.idl carla_msgs/msg/*idl carla_msgs/srv/*idl + ``` + * 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 adding suffixes e.g. "BLABLA" to the class and/or variable names and later perform a search and replace. + You might want to run the post_process_generated_file.sh within the generated code directory to take care on some issues observed with FastDDS generator 4.0.5 (including the BLABLA change). + Finally, you might face some linker issues, because the clashes within the idl files transfer partially into the C++ files, where you might have to move some functions into proper namespaces(i.e register_double__36_type_identifier and register_double__9_type_identifier). + Alternatively use the ros idl creation toolchain or wait until the generator is fixed and works properly. + * When switching to a new version of FastCdr, one has to keep in mind, that the generated files of the image-type have been adapted to allow for other allocators (i.e. carla::sensor::data::SerializerVectorAllocator) for the vector type to support copyless passing the memory rendered within Unreal to the deserialization function. That also required to extend the fastcdr header files located in the fastcdr subdirectory. But that implementation effort seemed worth for the sake of speed on image transfer. + + + + diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrive.cxx b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrive.cxx new file mode 100644 index 00000000000..2ad8100259d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrive.cxx @@ -0,0 +1,267 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "AckermannDrive.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace ackermann_msgs { + +namespace msg { + + + +AckermannDrive::AckermannDrive() +{ +} + +AckermannDrive::~AckermannDrive() +{ +} + +AckermannDrive::AckermannDrive( + const AckermannDrive& x) +{ + m_steering_angle = x.m_steering_angle; + m_steering_angle_velocity = x.m_steering_angle_velocity; + m_speed = x.m_speed; + m_acceleration = x.m_acceleration; + m_jerk = x.m_jerk; +} + +AckermannDrive::AckermannDrive( + AckermannDrive&& x) noexcept +{ + m_steering_angle = x.m_steering_angle; + m_steering_angle_velocity = x.m_steering_angle_velocity; + m_speed = x.m_speed; + m_acceleration = x.m_acceleration; + m_jerk = x.m_jerk; +} + +AckermannDrive& AckermannDrive::operator =( + const AckermannDrive& x) +{ + + m_steering_angle = x.m_steering_angle; + m_steering_angle_velocity = x.m_steering_angle_velocity; + m_speed = x.m_speed; + m_acceleration = x.m_acceleration; + m_jerk = x.m_jerk; + return *this; +} + +AckermannDrive& AckermannDrive::operator =( + AckermannDrive&& x) noexcept +{ + + m_steering_angle = x.m_steering_angle; + m_steering_angle_velocity = x.m_steering_angle_velocity; + m_speed = x.m_speed; + m_acceleration = x.m_acceleration; + m_jerk = x.m_jerk; + return *this; +} + +bool AckermannDrive::operator ==( + const AckermannDrive& x) const +{ + return (m_steering_angle == x.m_steering_angle && + m_steering_angle_velocity == x.m_steering_angle_velocity && + m_speed == x.m_speed && + m_acceleration == x.m_acceleration && + m_jerk == x.m_jerk); +} + +bool AckermannDrive::operator !=( + const AckermannDrive& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member steering_angle + * @param _steering_angle New value for member steering_angle + */ +void AckermannDrive::steering_angle( + float _steering_angle) +{ + m_steering_angle = _steering_angle; +} + +/*! + * @brief This function returns the value of member steering_angle + * @return Value of member steering_angle + */ +float AckermannDrive::steering_angle() const +{ + return m_steering_angle; +} + +/*! + * @brief This function returns a reference to member steering_angle + * @return Reference to member steering_angle + */ +float& AckermannDrive::steering_angle() +{ + return m_steering_angle; +} + + +/*! + * @brief This function sets a value in member steering_angle_velocity + * @param _steering_angle_velocity New value for member steering_angle_velocity + */ +void AckermannDrive::steering_angle_velocity( + float _steering_angle_velocity) +{ + m_steering_angle_velocity = _steering_angle_velocity; +} + +/*! + * @brief This function returns the value of member steering_angle_velocity + * @return Value of member steering_angle_velocity + */ +float AckermannDrive::steering_angle_velocity() const +{ + return m_steering_angle_velocity; +} + +/*! + * @brief This function returns a reference to member steering_angle_velocity + * @return Reference to member steering_angle_velocity + */ +float& AckermannDrive::steering_angle_velocity() +{ + return m_steering_angle_velocity; +} + + +/*! + * @brief This function sets a value in member speed + * @param _speed New value for member speed + */ +void AckermannDrive::speed( + float _speed) +{ + m_speed = _speed; +} + +/*! + * @brief This function returns the value of member speed + * @return Value of member speed + */ +float AckermannDrive::speed() const +{ + return m_speed; +} + +/*! + * @brief This function returns a reference to member speed + * @return Reference to member speed + */ +float& AckermannDrive::speed() +{ + return m_speed; +} + + +/*! + * @brief This function sets a value in member acceleration + * @param _acceleration New value for member acceleration + */ +void AckermannDrive::acceleration( + float _acceleration) +{ + m_acceleration = _acceleration; +} + +/*! + * @brief This function returns the value of member acceleration + * @return Value of member acceleration + */ +float AckermannDrive::acceleration() const +{ + return m_acceleration; +} + +/*! + * @brief This function returns a reference to member acceleration + * @return Reference to member acceleration + */ +float& AckermannDrive::acceleration() +{ + return m_acceleration; +} + + +/*! + * @brief This function sets a value in member jerk + * @param _jerk New value for member jerk + */ +void AckermannDrive::jerk( + float _jerk) +{ + m_jerk = _jerk; +} + +/*! + * @brief This function returns the value of member jerk + * @return Value of member jerk + */ +float AckermannDrive::jerk() const +{ + return m_jerk; +} + +/*! + * @brief This function returns a reference to member jerk + * @return Reference to member jerk + */ +float& AckermannDrive::jerk() +{ + return m_jerk; +} + + + + +} // namespace msg + + +} // namespace ackermann_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "AckermannDriveCdrAux.ipp" + 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..c5b482ec3e2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrive.h @@ -0,0 +1,253 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 +#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; +class CdrSizeCalculator; +} // 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(); + +private: + + float m_steering_angle{0.0}; + float m_steering_angle_velocity{0.0}; + float m_speed{0.0}; + float m_acceleration{0.0}; + float m_jerk{0.0}; + +}; + +} // namespace msg + +} // namespace ackermann_msgs + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveCdrAux.hpp new file mode 100644 index 00000000000..290f810a4a7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AckermannDriveCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVECDRAUX_HPP_ + +#include "AckermannDrive.h" + +constexpr uint32_t ackermann_msgs_msg_AckermannDrive_max_cdr_typesize {24UL}; +constexpr uint32_t ackermann_msgs_msg_AckermannDrive_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const ackermann_msgs::msg::AckermannDrive& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveCdrAux.ipp new file mode 100644 index 00000000000..ee5fc67f163 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveCdrAux.ipp @@ -0,0 +1,162 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AckermannDriveCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVECDRAUX_IPP_ + +#include "AckermannDriveCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const ackermann_msgs::msg::AckermannDrive& data, + size_t& current_alignment) +{ + using namespace ackermann_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.steering_angle(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.steering_angle_velocity(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.speed(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.acceleration(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.jerk(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const ackermann_msgs::msg::AckermannDrive& data) +{ + using namespace ackermann_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.steering_angle() + << eprosima::fastcdr::MemberId(1) << data.steering_angle_velocity() + << eprosima::fastcdr::MemberId(2) << data.speed() + << eprosima::fastcdr::MemberId(3) << data.acceleration() + << eprosima::fastcdr::MemberId(4) << data.jerk() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + ackermann_msgs::msg::AckermannDrive& data) +{ + using namespace ackermann_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.steering_angle(); + break; + + case 1: + dcdr >> data.steering_angle_velocity(); + break; + + case 2: + dcdr >> data.speed(); + break; + + case 3: + dcdr >> data.acceleration(); + break; + + case 4: + dcdr >> data.jerk(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const ackermann_msgs::msg::AckermannDrive& data) +{ + using namespace ackermann_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVECDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrivePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrivePubSubTypes.cxx new file mode 100644 index 00000000000..42fa2df5172 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrivePubSubTypes.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 AckermannDrivePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "AckermannDrivePubSubTypes.h" +#include "AckermannDriveCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace ackermann_msgs { +namespace msg { + + +AckermannDrivePubSubType::AckermannDrivePubSubType() +{ + setName("ackermann_msgs::msg::dds_::AckermannDrive_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(AckermannDrive::getMaxCdrSerializedSize()); +#else + ackermann_msgs_msg_AckermannDrive_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +AckermannDrivePubSubType::~AckermannDrivePubSubType() +{ +} + +bool AckermannDrivePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + AckermannDrive* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool AckermannDrivePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function AckermannDrivePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* AckermannDrivePubSubType::createData() +{ + return reinterpret_cast(new AckermannDrive()); +} + +void AckermannDrivePubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool AckermannDrivePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..df69d15df62 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDrivePubSubTypes.h @@ -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 AckermannDrivePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "AckermannDrive.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~AckermannDrivePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace ackermann_msgs + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVE_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStamped.cxx b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStamped.cxx new file mode 100644 index 00000000000..926f11776da --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStamped.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 AckermannDriveStamped.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "AckermannDriveStamped.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace ackermann_msgs { + +namespace msg { + + + +AckermannDriveStamped::AckermannDriveStamped() +{ +} + +AckermannDriveStamped::~AckermannDriveStamped() +{ +} + +AckermannDriveStamped::AckermannDriveStamped( + const AckermannDriveStamped& x) +{ + m_header = x.m_header; + m_drive = x.m_drive; +} + +AckermannDriveStamped::AckermannDriveStamped( + AckermannDriveStamped&& x) noexcept +{ + m_header = std::move(x.m_header); + m_drive = std::move(x.m_drive); +} + +AckermannDriveStamped& AckermannDriveStamped::operator =( + const AckermannDriveStamped& x) +{ + + m_header = x.m_header; + m_drive = x.m_drive; + return *this; +} + +AckermannDriveStamped& AckermannDriveStamped::operator =( + AckermannDriveStamped&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_drive = std::move(x.m_drive); + return *this; +} + +bool AckermannDriveStamped::operator ==( + const AckermannDriveStamped& x) const +{ + return (m_header == x.m_header && + m_drive == x.m_drive); +} + +bool AckermannDriveStamped::operator !=( + const AckermannDriveStamped& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void AckermannDriveStamped::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 AckermannDriveStamped::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& AckermannDriveStamped::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& AckermannDriveStamped::header() +{ + return m_header; +} + + +/*! + * @brief This function copies the value in member drive + * @param _drive New value to be copied in member drive + */ +void AckermannDriveStamped::drive( + const ackermann_msgs::msg::AckermannDrive& _drive) +{ + m_drive = _drive; +} + +/*! + * @brief This function moves the value in member drive + * @param _drive New value to be moved in member drive + */ +void AckermannDriveStamped::drive( + ackermann_msgs::msg::AckermannDrive&& _drive) +{ + m_drive = std::move(_drive); +} + +/*! + * @brief This function returns a constant reference to member drive + * @return Constant reference to member drive + */ +const ackermann_msgs::msg::AckermannDrive& AckermannDriveStamped::drive() const +{ + return m_drive; +} + +/*! + * @brief This function returns a reference to member drive + * @return Reference to member drive + */ +ackermann_msgs::msg::AckermannDrive& AckermannDriveStamped::drive() +{ + return m_drive; +} + + + + +} // namespace msg + + +} // namespace ackermann_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "AckermannDriveStampedCdrAux.ipp" + 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..93e36456d8d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStamped.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_H_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "AckermannDrive.h" +#include "std_msgs/msg/Header.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedCdrAux.hpp new file mode 100644 index 00000000000..874f0e3b505 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AckermannDriveStampedCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPEDCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPEDCDRAUX_HPP_ + +#include "AckermannDriveStamped.h" + +constexpr uint32_t ackermann_msgs_msg_AckermannDriveStamped_max_cdr_typesize {304UL}; +constexpr uint32_t ackermann_msgs_msg_AckermannDriveStamped_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const ackermann_msgs::msg::AckermannDriveStamped& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPEDCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedCdrAux.ipp new file mode 100644 index 00000000000..810db5ccb82 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AckermannDriveStampedCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPEDCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPEDCDRAUX_IPP_ + +#include "AckermannDriveStampedCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const ackermann_msgs::msg::AckermannDriveStamped& data, + size_t& current_alignment) +{ + using namespace ackermann_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.drive(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const ackermann_msgs::msg::AckermannDriveStamped& data) +{ + using namespace ackermann_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.drive() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + ackermann_msgs::msg::AckermannDriveStamped& data) +{ + using namespace ackermann_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.drive(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const ackermann_msgs::msg::AckermannDriveStamped& data) +{ + using namespace ackermann_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPEDCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.cxx new file mode 100644 index 00000000000..1a8d35279e8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.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 AckermannDriveStampedPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "AckermannDriveStampedPubSubTypes.h" +#include "AckermannDriveStampedCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace ackermann_msgs { +namespace msg { + + +AckermannDriveStampedPubSubType::AckermannDriveStampedPubSubType() +{ + setName("ackermann_msgs::msg::dds_::AckermannDriveStamped_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(AckermannDriveStamped::getMaxCdrSerializedSize()); +#else + ackermann_msgs_msg_AckermannDriveStamped_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +AckermannDriveStampedPubSubType::~AckermannDriveStampedPubSubType() +{ +} + +bool AckermannDriveStampedPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + AckermannDriveStamped* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool AckermannDriveStampedPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function AckermannDriveStampedPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* AckermannDriveStampedPubSubType::createData() +{ + return reinterpret_cast(new AckermannDriveStamped()); +} + +void AckermannDriveStampedPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool AckermannDriveStampedPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..8288d4bdaa7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "AckermannDriveStamped.h" + +#include "AckermannDrivePubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~AckermannDriveStampedPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace ackermann_msgs + +#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/Time.cxx b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/Time.cxx new file mode 100644 index 00000000000..ceed6b49dd6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/Time.cxx @@ -0,0 +1,165 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Time.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace builtin_interfaces { + +namespace msg { + + + +Time::Time() +{ +} + +Time::~Time() +{ +} + +Time::Time( + const Time& x) +{ + m_sec = x.m_sec; + m_nanosec = x.m_nanosec; +} + +Time::Time( + Time&& x) noexcept +{ + m_sec = x.m_sec; + m_nanosec = x.m_nanosec; +} + +Time& Time::operator =( + const Time& x) +{ + + m_sec = x.m_sec; + m_nanosec = x.m_nanosec; + return *this; +} + +Time& Time::operator =( + Time&& x) noexcept +{ + + m_sec = x.m_sec; + m_nanosec = x.m_nanosec; + return *this; +} + +bool Time::operator ==( + const Time& x) const +{ + return (m_sec == x.m_sec && + m_nanosec == x.m_nanosec); +} + +bool Time::operator !=( + const Time& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member sec + * @param _sec New value for member sec + */ +void Time::sec( + int32_t _sec) +{ + m_sec = _sec; +} + +/*! + * @brief This function returns the value of member sec + * @return Value of member sec + */ +int32_t Time::sec() const +{ + return m_sec; +} + +/*! + * @brief This function returns a reference to member sec + * @return Reference to member sec + */ +int32_t& Time::sec() +{ + return m_sec; +} + + +/*! + * @brief This function sets a value in member nanosec + * @param _nanosec New value for member nanosec + */ +void Time::nanosec( + uint32_t _nanosec) +{ + m_nanosec = _nanosec; +} + +/*! + * @brief This function returns the value of member nanosec + * @return Value of member nanosec + */ +uint32_t Time::nanosec() const +{ + return m_nanosec; +} + +/*! + * @brief This function returns a reference to member nanosec + * @return Reference to member nanosec + */ +uint32_t& Time::nanosec() +{ + return m_nanosec; +} + + + + +} // namespace msg + + +} // namespace builtin_interfaces +// Include auxiliary functions like for serializing/deserializing. +#include "TimeCdrAux.ipp" + 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..cf8e94b6c9b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/Time.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 Time.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_H_ +#define _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_H_ + +#include +#include +#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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int32_t m_sec{0}; + uint32_t m_nanosec{0}; + +}; + +} // namespace msg + +} // namespace builtin_interfaces + +#endif // _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimeCdrAux.hpp new file mode 100644 index 00000000000..8ff3a974f9e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimeCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TimeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIMECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIMECDRAUX_HPP_ + +#include "Time.h" + +constexpr uint32_t builtin_interfaces_msg_Time_max_cdr_typesize {12UL}; +constexpr uint32_t builtin_interfaces_msg_Time_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const builtin_interfaces::msg::Time& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIMECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimeCdrAux.ipp new file mode 100644 index 00000000000..6cb341cd620 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimeCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TimeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIMECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIMECDRAUX_IPP_ + +#include "TimeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const builtin_interfaces::msg::Time& data, + size_t& current_alignment) +{ + using namespace builtin_interfaces::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.sec(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.nanosec(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const builtin_interfaces::msg::Time& data) +{ + using namespace builtin_interfaces::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.sec() + << eprosima::fastcdr::MemberId(1) << data.nanosec() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + builtin_interfaces::msg::Time& data) +{ + using namespace builtin_interfaces::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.sec(); + break; + + case 1: + dcdr >> data.nanosec(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const builtin_interfaces::msg::Time& data) +{ + using namespace builtin_interfaces::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIMECDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimePubSubTypes.cxx new file mode 100644 index 00000000000..2c418f22641 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimePubSubTypes.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 TimePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "TimePubSubTypes.h" +#include "TimeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace builtin_interfaces { +namespace msg { + + +TimePubSubType::TimePubSubType() +{ + setName("builtin_interfaces::msg::dds_::Time_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Time::getMaxCdrSerializedSize()); +#else + builtin_interfaces_msg_Time_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +TimePubSubType::~TimePubSubType() +{ +} + +bool TimePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Time* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool TimePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + Time* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function TimePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* TimePubSubType::createData() +{ + return reinterpret_cast(new Time()); +} + +void TimePubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool TimePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..3de3c15477d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/builtin_interfaces/msg/TimePubSubTypes.h @@ -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 TimePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Time.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~TimePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace builtin_interfaces + +#endif // _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_PUBSUBTYPES_H_ + 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..a767ea0ed0d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsDomainParticipantImpl.cpp @@ -0,0 +1,52 @@ +// 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 "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"); + } + carla::log_debug("DdsDomainParticipantImpl::Constructor()"); +} + +DdsDomainParticipantImpl::~DdsDomainParticipantImpl() { + carla::log_debug("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..b30522ca649 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsDomainParticipantImpl.h @@ -0,0 +1,30 @@ + +// 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 + +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..e33498e038e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsPublisherImpl.h @@ -0,0 +1,179 @@ +// 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 "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_debug("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 wqos = DataWriterQos(qos); + wqos.endpoint().history_memory_policy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE; + return InitInternal(domain_participant, topic_name, wqos); + } + + bool Init(std::shared_ptr domain_participant, std::string topic_name, ROS2QoS qos) { + auto wqos = DataWriterQos(qos); + return InitInternal(domain_participant, topic_name, wqos); + } + + bool Publish() override { + if (_message_updated) { + carla::log_verbose("DdsPublisherImpl[", _topic->get_name(), "]::Publishing() updated message"); + 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) { + _message_updated = false; + } else { + carla::log_error("DdsPublisherImpl[", _topic->get_name(), "]::Publish() Failed to write data; Error ", + std::to_string(rcode)); + } + carla::log_verbose("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::DataWriterQos const& wqos) { + carla::log_debug("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); + + auto const pubqos = eprosima::fastdds::dds::PUBLISHER_QOS_DEFAULT; + _publisher = _participant->create_publisher(pubqos); + if (_publisher == nullptr) { + carla::log_error("DdsPublisherImpl[", _type->getName(), "]::Init() Failed to create Publisher"); + return false; + } + + auto const tqos = eprosima::fastdds::dds::TOPIC_QOS_DEFAULT; + _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_debug("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..5d55c181aa3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsQoS.h @@ -0,0 +1,59 @@ +// 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 "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.resource_limits().max_samples = 1000; + fast_dds_qos.resource_limits().allocated_samples = qos._history_depth; + } + return fast_dds_qos; +} + +inline eprosima::fastdds::dds::DataWriterQos DataWriterQos(ROS2QoS const &qos) { + auto writer_qos = FastDdsQos(qos); + + if ( qos._force_synchronous_writer ) { + writer_qos.publish_mode().kind = eprosima::fastdds::dds::SYNCHRONOUS_PUBLISH_MODE; + } + return writer_qos; +} + +inline eprosima::fastdds::dds::DataReaderQos DataReaderQos(ROS2QoS const &qos) { + return FastDdsQos(qos); +} + + +} // 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..295785c7934 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsReturnCode.h @@ -0,0 +1,48 @@ +// 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 + +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..4fb40850f01 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsServiceImpl.h @@ -0,0 +1,249 @@ +// 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 "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_debug("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_debug("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; + _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_LAST_HISTORY_QOS; + datareader_qos.history().depth = 50; + datareader_qos.reliability().kind = eprosima::fastdds::dds::RELIABLE_RELIABILITY_QOS; + datareader_qos.durability().kind = eprosima::fastdds::dds::VOLATILE_DURABILITY_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_LAST_HISTORY_QOS; + writer_qos.history().depth = 10; + writer_qos.durability().kind = eprosima::fastdds::dds::VOLATILE_DURABILITY_QOS; + writer_qos.reliability().kind = eprosima::fastdds::dds::RELIABLE_RELIABILITY_QOS; + writer_qos.publish_mode().kind = eprosima::fastdds::dds::SYNCHRONOUS_PUBLISH_MODE; + _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 SyncServiceCallbackType = std::function; + void SetSyncServiceCallback(SyncServiceCallbackType callback) { + _sync_callback = callback; + } + + using RequestPtrType = std::shared_ptr; + using AsyncServiceCallbackType = std::function; + void SetAsyncServiceCallback(AsyncServiceCallbackType callback) { + _async_callback = callback; + } + + void on_data_available(eprosima::fastdds::dds::DataReader* reader) override { + auto incoming_request = std::make_shared(); + eprosima::fastrtps::types::ReturnCode_t rcode = reader->take_next_sample(&incoming_request->request, &incoming_request->info); + if (rcode == eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_OK) { + if (eprosima::fastdds::dds::InstanceStateKind::ALIVE_INSTANCE_STATE == incoming_request->info.instance_state) { + carla::log_debug("DdsServiceImpl[", _request_topic->get_name(), "]::on_data_available(): Incoming request "); + _incoming_requests.push_back(incoming_request); + } 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 { + while (!_incoming_requests.empty()) { + carla::log_debug("DdsServiceImpl[", _request_topic->get_name(), "]::CheckRequest(): New Request"); + auto const incoming_request = _incoming_requests.front(); + if ( _sync_callback) { + carla::log_debug("DdsServiceImpl[", _request_topic->get_name(), "]::CheckRequest(): Calling sync callback"); + auto response = _sync_callback(incoming_request->request); + carla::log_debug("DdsServiceImpl[", _request_topic->get_name(), "]::CheckRequest(): Sync callback returned"); + SendResponseInternal(response, incoming_request->info.sample_identity); + } else if (_async_callback) { + carla::log_debug("DdsServiceImpl[", _request_topic->get_name(), "]::CheckRequest(): Calling async callback"); + _pending_async_requests.push_back(incoming_request); + auto request_ptr = std::shared_ptr(incoming_request, &incoming_request->request); + _async_callback(request_ptr); + } else { + carla::log_warning("DdsServiceImpl[", _request_topic->get_name(), + "]::CheckRequest(): No sync or async callback defined yet"); + } + _incoming_requests.pop_front(); + } + } + + void SendResponse(RequestPtrType request_ptr, RESPONSE_TYPE response) { + carla::log_debug("DdsServiceImpl[", _request_topic->get_name(), "]::SendResponse(): Sending async response"); + auto it = std::find_if(_pending_async_requests.begin(), _pending_async_requests.end(), + [request_ptr](std::shared_ptr const& pending_request) { + return &pending_request->request == request_ptr.get(); + }); + if (it != _pending_async_requests.end()) { + SendResponseInternal(response, it->get()->info.sample_identity); + _pending_async_requests.erase(it); + } else { + carla::log_error("DdsServiceImpl[", _request_topic->get_name(), + "]::SendResponse(): Could not find matching pending request for async response"); + } + } +private: + void SendResponseInternal(RESPONSE_TYPE& response, const eprosima::fastrtps::rtps::SampleIdentity& related_request_identity) { + eprosima::fastrtps::rtps::WriteParams write_params; + + write_params.related_sample_identity() = related_request_identity; + eprosima::fastrtps::types::ReturnCode_t rcode = _datawriter->write(&response, write_params); + if (rcode != eprosima::fastrtps::types::ReturnCode_t::ReturnCodeValue::RETCODE_OK) { + carla::log_debug("DdsServiceImpl[", _response_topic->get_name(), + "]::SendResponse() Failed to write data; Error ", std::to_string(rcode), " , ", related_request_identity.sequence_number()); + } + carla::log_debug("DdsServiceImpl[", _response_topic->get_name(), "]::SendResponse() Response sent"); + } + + 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}; + + SyncServiceCallbackType _sync_callback{nullptr}; + AsyncServiceCallbackType _async_callback{nullptr}; + + struct IncomingRequest { + REQUEST_TYPE request{}; + eprosima::fastdds::dds::SampleInfo info; + }; + std::deque> _incoming_requests; + + std::list> _pending_async_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..f4a7fc1ace0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla/ros2/impl/DdsSubscriberImpl.h @@ -0,0 +1,169 @@ +// 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 "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_debug("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 rqos = DataReaderQos(qos); + return InitInternal(domain_participant, topic_name, 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; + eprosima::fastrtps::types::ReturnCode_t 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::DataReaderQos const& rqos) { + carla::log_debug("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); + + auto const subqos = eprosima::fastdds::dds::SUBSCRIBER_QOS_DEFAULT; + _subscriber = _participant->create_subscriber(subqos); + if (_subscriber == nullptr) { + carla::log_error("DdsSubscriberImpl[", topic_name, "]::Init(): Failed to create Subscriber"); + return false; + } + + auto const tqos = eprosima::fastdds::dds::TOPIC_QOS_DEFAULT; + _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..7d511be9b1c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprint.cxx @@ -0,0 +1,231 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + + + +CarlaActorBlueprint::CarlaActorBlueprint() +{ +} + +CarlaActorBlueprint::~CarlaActorBlueprint() +{ +} + +CarlaActorBlueprint::CarlaActorBlueprint( + const CarlaActorBlueprint& x) +{ + m_id = x.m_id; + m_tags = x.m_tags; + m_attributes = x.m_attributes; +} + +CarlaActorBlueprint::CarlaActorBlueprint( + CarlaActorBlueprint&& x) noexcept +{ + m_id = std::move(x.m_id); + m_tags = std::move(x.m_tags); + m_attributes = std::move(x.m_attributes); +} + +CarlaActorBlueprint& CarlaActorBlueprint::operator =( + const CarlaActorBlueprint& x) +{ + + m_id = x.m_id; + m_tags = x.m_tags; + m_attributes = x.m_attributes; + return *this; +} + +CarlaActorBlueprint& CarlaActorBlueprint::operator =( + CarlaActorBlueprint&& x) noexcept +{ + + m_id = std::move(x.m_id); + m_tags = std::move(x.m_tags); + m_attributes = std::move(x.m_attributes); + return *this; +} + +bool CarlaActorBlueprint::operator ==( + const CarlaActorBlueprint& x) const +{ + return (m_id == x.m_id && + m_tags == x.m_tags && + m_attributes == x.m_attributes); +} + +bool CarlaActorBlueprint::operator !=( + const CarlaActorBlueprint& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member id + * @param _id New value to be copied in member id + */ +void 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 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& CarlaActorBlueprint::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +std::string& 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 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 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& CarlaActorBlueprint::tags() const +{ + return m_tags; +} + +/*! + * @brief This function returns a reference to member tags + * @return Reference to member tags + */ +std::vector& 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 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 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& CarlaActorBlueprint::attributes() const +{ + return m_attributes; +} + +/*! + * @brief This function returns a reference to member attributes + * @return Reference to member attributes + */ +std::vector& CarlaActorBlueprint::attributes() +{ + return m_attributes; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaActorBlueprintCdrAux.ipp" + 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..527a3d6bc40 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprint.h @@ -0,0 +1,235 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "diagnostic_msgs/msg/KeyValue.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintCdrAux.hpp new file mode 100644 index 00000000000..ecd0d94fd63 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaActorBlueprintCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINTCDRAUX_HPP_ + +#include "CarlaActorBlueprint.h" + +constexpr uint32_t carla_msgs_msg_CarlaActorBlueprint_max_cdr_typesize {78680UL}; +constexpr uint32_t carla_msgs_msg_CarlaActorBlueprint_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaActorBlueprint& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintCdrAux.ipp new file mode 100644 index 00000000000..722c6db2941 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintCdrAux.ipp @@ -0,0 +1,148 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaActorBlueprintCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINTCDRAUX_IPP_ + +#include "CarlaActorBlueprintCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaActorBlueprint& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.tags(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.attributes(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaActorBlueprint& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.id() + << eprosima::fastcdr::MemberId(1) << data.tags() + << eprosima::fastcdr::MemberId(2) << data.attributes() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaActorBlueprint& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.id(); + break; + + case 1: + dcdr >> data.tags(); + break; + + case 2: + dcdr >> data.attributes(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaActorBlueprint& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINTCDRAUX_IPP_ + 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..919dc1bef1a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintPubSubTypes.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 CarlaActorBlueprintPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaActorBlueprintPubSubTypes.h" +#include "CarlaActorBlueprintCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + + + +CarlaActorBlueprintPubSubType::CarlaActorBlueprintPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaActorBlueprint_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaActorBlueprint::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaActorBlueprint_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaActorBlueprintPubSubType::~CarlaActorBlueprintPubSubType() +{ +} + +bool CarlaActorBlueprintPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaActorBlueprintPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaActorBlueprintPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..1e614a2a704 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorBlueprintPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaActorBlueprint.h" + +#include "diagnostic_msgs/msg/KeyValuePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaActorBlueprintPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORBLUEPRINT_PUBSUBTYPES_H_ + 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..59c2c13199a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfo.cxx @@ -0,0 +1,557 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + +namespace CarlaActorInfo_Constants { + + +} // namespace CarlaActorInfo_Constants + + + + +CarlaActorInfo::CarlaActorInfo() +{ +} + +CarlaActorInfo::~CarlaActorInfo() +{ +} + +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; + m_frame_id = x.m_frame_id; + m_city_object_label = x.m_city_object_label; + m_attributes = x.m_attributes; +} + +CarlaActorInfo::CarlaActorInfo( + CarlaActorInfo&& x) noexcept +{ + 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); + m_frame_id = std::move(x.m_frame_id); + m_city_object_label = x.m_city_object_label; + m_attributes = std::move(x.m_attributes); +} + +CarlaActorInfo& 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; + m_frame_id = x.m_frame_id; + m_city_object_label = x.m_city_object_label; + m_attributes = x.m_attributes; + return *this; +} + +CarlaActorInfo& CarlaActorInfo::operator =( + CarlaActorInfo&& x) noexcept +{ + + 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); + m_frame_id = std::move(x.m_frame_id); + m_city_object_label = x.m_city_object_label; + m_attributes = std::move(x.m_attributes); + return *this; +} + +bool 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 && + m_frame_id == x.m_frame_id && + m_city_object_label == x.m_city_object_label && + m_attributes == x.m_attributes); +} + +bool CarlaActorInfo::operator !=( + const CarlaActorInfo& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void CarlaActorInfo::id( + uint64_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint64_t CarlaActorInfo::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint64_t& 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 CarlaActorInfo::parent_id( + uint64_t _parent_id) +{ + m_parent_id = _parent_id; +} + +/*! + * @brief This function returns the value of member parent_id + * @return Value of member parent_id + */ +uint64_t CarlaActorInfo::parent_id() const +{ + return m_parent_id; +} + +/*! + * @brief This function returns a reference to member parent_id + * @return Reference to member parent_id + */ +uint64_t& 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 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 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& CarlaActorInfo::type() const +{ + return m_type; +} + +/*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ +std::string& 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 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 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& CarlaActorInfo::rosname() const +{ + return m_rosname; +} + +/*! + * @brief This function returns a reference to member rosname + * @return Reference to member rosname + */ +std::string& 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 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 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& CarlaActorInfo::rolename() const +{ + return m_rolename; +} + +/*! + * @brief This function returns a reference to member rolename + * @return Reference to member rolename + */ +std::string& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& CarlaActorInfo::topic_prefix() +{ + return m_topic_prefix; +} + + +/*! + * @brief This function copies the value in member frame_id + * @param _frame_id New value to be copied in member frame_id + */ +void CarlaActorInfo::frame_id( + const std::string& _frame_id) +{ + m_frame_id = _frame_id; +} + +/*! + * @brief This function moves the value in member frame_id + * @param _frame_id New value to be moved in member frame_id + */ +void CarlaActorInfo::frame_id( + std::string&& _frame_id) +{ + m_frame_id = std::move(_frame_id); +} + +/*! + * @brief This function returns a constant reference to member frame_id + * @return Constant reference to member frame_id + */ +const std::string& CarlaActorInfo::frame_id() const +{ + return m_frame_id; +} + +/*! + * @brief This function returns a reference to member frame_id + * @return Reference to member frame_id + */ +std::string& CarlaActorInfo::frame_id() +{ + return m_frame_id; +} + + +/*! + * @brief This function sets a value in member city_object_label + * @param _city_object_label New value for member city_object_label + */ +void CarlaActorInfo::city_object_label( + uint8_t _city_object_label) +{ + m_city_object_label = _city_object_label; +} + +/*! + * @brief This function returns the value of member city_object_label + * @return Value of member city_object_label + */ +uint8_t CarlaActorInfo::city_object_label() const +{ + return m_city_object_label; +} + +/*! + * @brief This function returns a reference to member city_object_label + * @return Reference to member city_object_label + */ +uint8_t& CarlaActorInfo::city_object_label() +{ + return m_city_object_label; +} + + +/*! + * @brief This function copies the value in member attributes + * @param _attributes New value to be copied in member attributes + */ +void CarlaActorInfo::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 CarlaActorInfo::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& CarlaActorInfo::attributes() const +{ + return m_attributes; +} + +/*! + * @brief This function returns a reference to member attributes + * @return Reference to member attributes + */ +std::vector& CarlaActorInfo::attributes() +{ + return m_attributes; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaActorInfoCdrAux.ipp" + 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..2944daf797f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfo.h @@ -0,0 +1,472 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "diagnostic_msgs/msg/KeyValue.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(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; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + +namespace CarlaActorInfo_Constants { + +const uint8_t CITYOBJECTLABEL_NONE = 0; +const uint8_t CITYOBJECTLABEL_ROADS = 1; +const uint8_t CITYOBJECTLABEL_SIDEWALKS = 2; +const uint8_t CITYOBJECTLABEL_BUILDINGS = 3; +const uint8_t CITYOBJECTLABEL_WALLS = 4; +const uint8_t CITYOBJECTLABEL_FENCES = 5; +const uint8_t CITYOBJECTLABEL_POLES = 6; +const uint8_t CITYOBJECTLABEL_TRAFFICLIGHT = 7; +const uint8_t CITYOBJECTLABEL_TRAFFICSIGNS = 8; +const uint8_t CITYOBJECTLABEL_VEGETATION = 9; +const uint8_t CITYOBJECTLABEL_TERRAIN = 10; +const uint8_t CITYOBJECTLABEL_SKY = 11; +const uint8_t CITYOBJECTLABEL_PEDESTRIANS = 12; +const uint8_t CITYOBJECTLABEL_RIDER = 13; +const uint8_t CITYOBJECTLABEL_CAR = 14; +const uint8_t CITYOBJECTLABEL_TRUCK = 15; +const uint8_t CITYOBJECTLABEL_BUS = 16; +const uint8_t CITYOBJECTLABEL_TRAIN = 17; +const uint8_t CITYOBJECTLABEL_MOTORCYCLE = 18; +const uint8_t CITYOBJECTLABEL_BICYCLE = 19; +const uint8_t CITYOBJECTLABEL_STATIC = 20; +const uint8_t CITYOBJECTLABEL_DYNAMIC = 21; +const uint8_t CITYOBJECTLABEL_OTHER = 22; +const uint8_t CITYOBJECTLABEL_WATER = 23; +const uint8_t CITYOBJECTLABEL_ROADLINES = 24; +const uint8_t CITYOBJECTLABEL_GROUND = 25; +const uint8_t CITYOBJECTLABEL_BRIDGE = 26; +const uint8_t CITYOBJECTLABEL_RAILTRACK = 27; +const uint8_t CITYOBJECTLABEL_GUARDRAIL = 28; +const uint8_t CITYOBJECTLABEL_ANY = 255; + +} // namespace CarlaActorInfo_Constants + + + + +/*! + * @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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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( + uint64_t _id); + + /*! + * @brief This function returns the value of member id + * @return Value of member id + */ + eProsima_user_DllExport uint64_t id() const; + + /*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ + eProsima_user_DllExport uint64_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( + uint64_t _parent_id); + + /*! + * @brief This function returns the value of member parent_id + * @return Value of member parent_id + */ + eProsima_user_DllExport uint64_t parent_id() const; + + /*! + * @brief This function returns a reference to member parent_id + * @return Reference to member parent_id + */ + eProsima_user_DllExport uint64_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 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 sets a value in member city_object_label + * @param _city_object_label New value for member city_object_label + */ + eProsima_user_DllExport void city_object_label( + uint8_t _city_object_label); + + /*! + * @brief This function returns the value of member city_object_label + * @return Value of member city_object_label + */ + eProsima_user_DllExport uint8_t city_object_label() const; + + /*! + * @brief This function returns a reference to member city_object_label + * @return Reference to member city_object_label + */ + eProsima_user_DllExport uint8_t& city_object_label(); + + + /*! + * @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(); + +private: + + uint64_t m_id{0}; + uint64_t m_parent_id{0}; + 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; + std::string m_frame_id; + uint8_t m_city_object_label{0}; + std::vector m_attributes; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoCdrAux.hpp new file mode 100644 index 00000000000..9580e25668e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoCdrAux.hpp @@ -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 CarlaActorInfoCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFOCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFOCDRAUX_HPP_ + +#include "CarlaActorInfo.h" + +constexpr uint32_t carla_msgs_msg_CarlaActorInfo_max_cdr_typesize {54256UL}; +constexpr uint32_t carla_msgs_msg_CarlaActorInfo_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaActorInfo& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFOCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoCdrAux.ipp new file mode 100644 index 00000000000..5a8a8e99512 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoCdrAux.ipp @@ -0,0 +1,273 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaActorInfoCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFOCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFOCDRAUX_IPP_ + +#include "CarlaActorInfoCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaActorInfo& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.parent_id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.rosname(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.rolename(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.object_type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.base_type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.topic_prefix(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.frame_id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), + data.city_object_label(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(10), + data.attributes(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaActorInfo& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.id() + << eprosima::fastcdr::MemberId(1) << data.parent_id() + << eprosima::fastcdr::MemberId(2) << data.type() + << eprosima::fastcdr::MemberId(3) << data.rosname() + << eprosima::fastcdr::MemberId(4) << data.rolename() + << eprosima::fastcdr::MemberId(5) << data.object_type() + << eprosima::fastcdr::MemberId(6) << data.base_type() + << eprosima::fastcdr::MemberId(7) << data.topic_prefix() + << eprosima::fastcdr::MemberId(8) << data.frame_id() + << eprosima::fastcdr::MemberId(9) << data.city_object_label() + << eprosima::fastcdr::MemberId(10) << data.attributes() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaActorInfo& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.id(); + break; + + case 1: + dcdr >> data.parent_id(); + break; + + case 2: + dcdr >> data.type(); + break; + + case 3: + dcdr >> data.rosname(); + break; + + case 4: + dcdr >> data.rolename(); + break; + + case 5: + dcdr >> data.object_type(); + break; + + case 6: + dcdr >> data.base_type(); + break; + + case 7: + dcdr >> data.topic_prefix(); + break; + + case 8: + dcdr >> data.frame_id(); + break; + + case 9: + dcdr >> data.city_object_label(); + break; + + case 10: + dcdr >> data.attributes(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaActorInfo& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFOCDRAUX_IPP_ + 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..bc29e9cc244 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoPubSubTypes.cxx @@ -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 CarlaActorInfoPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaActorInfoPubSubTypes.h" +#include "CarlaActorInfoCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { +namespace CarlaActorInfo_Constants { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} //End of namespace CarlaActorInfo_Constants + + + + + +CarlaActorInfoPubSubType::CarlaActorInfoPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaActorInfo_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaActorInfo::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaActorInfo_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaActorInfoPubSubType::~CarlaActorInfoPubSubType() +{ +} + +bool CarlaActorInfoPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaActorInfoPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaActorInfoPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoPubSubTypes.h new file mode 100644 index 00000000000..fa163221697 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorInfoPubSubTypes.h @@ -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 CarlaActorInfoPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaActorInfo.h" + +#include "diagnostic_msgs/msg/KeyValuePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaActorInfo is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs { +namespace msg { +namespace CarlaActorInfo_Constants { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} // namespace CarlaActorInfo_Constants + + + + + +/*! + * @brief This class represents the TopicDataType of the type CarlaActorInfo defined by the user in the IDL file. + * @ingroup CarlaActorInfo + */ +class CarlaActorInfoPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaActorInfo type; + + eProsima_user_DllExport CarlaActorInfoPubSubType(); + + eProsima_user_DllExport ~CarlaActorInfoPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORINFO_PUBSUBTYPES_H_ + 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..d3bdee932aa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorList.cxx @@ -0,0 +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 CarlaActorList.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + + + +CarlaActorList::CarlaActorList() +{ +} + +CarlaActorList::~CarlaActorList() +{ +} + +CarlaActorList::CarlaActorList( + const CarlaActorList& x) +{ + m_actors = x.m_actors; +} + +CarlaActorList::CarlaActorList( + CarlaActorList&& x) noexcept +{ + m_actors = std::move(x.m_actors); +} + +CarlaActorList& CarlaActorList::operator =( + const CarlaActorList& x) +{ + + m_actors = x.m_actors; + return *this; +} + +CarlaActorList& CarlaActorList::operator =( + CarlaActorList&& x) noexcept +{ + + m_actors = std::move(x.m_actors); + return *this; +} + +bool CarlaActorList::operator ==( + const CarlaActorList& x) const +{ + return (m_actors == x.m_actors); +} + +bool CarlaActorList::operator !=( + const CarlaActorList& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member actors + * @param _actors New value to be copied in member actors + */ +void 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 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& CarlaActorList::actors() const +{ + return m_actors; +} + +/*! + * @brief This function returns a reference to member actors + * @return Reference to member actors + */ +std::vector& CarlaActorList::actors() +{ + return m_actors; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaActorListCdrAux.ipp" + 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..745e3efb59d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorList.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CarlaActorInfo.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_actors; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListCdrAux.hpp new file mode 100644 index 00000000000..3324d15e495 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListCdrAux.hpp @@ -0,0 +1,54 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaActorListCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLISTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLISTCDRAUX_HPP_ + +#include "CarlaActorList.h" + +constexpr uint32_t carla_msgs_msg_CarlaActorList_max_cdr_typesize {5425608UL}; +constexpr uint32_t carla_msgs_msg_CarlaActorList_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaActorList& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLISTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListCdrAux.ipp new file mode 100644 index 00000000000..6e6b0a0fdb2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListCdrAux.ipp @@ -0,0 +1,132 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaActorListCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLISTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLISTCDRAUX_IPP_ + +#include "CarlaActorListCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaActorList& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.actors(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaActorList& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.actors() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaActorList& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.actors(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaActorList& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLISTCDRAUX_IPP_ + 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..710e0695c7b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListPubSubTypes.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 CarlaActorListPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaActorListPubSubTypes.h" +#include "CarlaActorListCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + + + +CarlaActorListPubSubType::CarlaActorListPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaActorList_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaActorList::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaActorList_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaActorListPubSubType::~CarlaActorListPubSubType() +{ +} + +bool CarlaActorListPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaActorListPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaActorListPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..c66482d6635 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaActorListPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaActorList.h" + +#include "CarlaActorInfoPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaActorListPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAACTORLIST_PUBSUBTYPES_H_ + 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..33f62ae230d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBox.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 CarlaBoundingBox.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaBoundingBox::CarlaBoundingBox() +{ +} + +CarlaBoundingBox::~CarlaBoundingBox() +{ +} + +CarlaBoundingBox::CarlaBoundingBox( + const CarlaBoundingBox& x) +{ + m_center = x.m_center; + m_size = x.m_size; +} + +CarlaBoundingBox::CarlaBoundingBox( + CarlaBoundingBox&& x) noexcept +{ + m_center = std::move(x.m_center); + m_size = std::move(x.m_size); +} + +CarlaBoundingBox& CarlaBoundingBox::operator =( + const CarlaBoundingBox& x) +{ + + m_center = x.m_center; + m_size = x.m_size; + return *this; +} + +CarlaBoundingBox& CarlaBoundingBox::operator =( + CarlaBoundingBox&& x) noexcept +{ + + m_center = std::move(x.m_center); + m_size = std::move(x.m_size); + return *this; +} + +bool CarlaBoundingBox::operator ==( + const CarlaBoundingBox& x) const +{ + return (m_center == x.m_center && + m_size == x.m_size); +} + +bool CarlaBoundingBox::operator !=( + const CarlaBoundingBox& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member center + * @param _center New value to be copied in member center + */ +void 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 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& CarlaBoundingBox::center() const +{ + return m_center; +} + +/*! + * @brief This function returns a reference to member center + * @return Reference to member center + */ +geometry_msgs::msg::Vector3& 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 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 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& CarlaBoundingBox::size() const +{ + return m_size; +} + +/*! + * @brief This function returns a reference to member size + * @return Reference to member size + */ +geometry_msgs::msg::Vector3& CarlaBoundingBox::size() +{ + return m_size; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaBoundingBoxCdrAux.ipp" + 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..76ca610cbb5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBox.h @@ -0,0 +1,205 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "geometry_msgs/msg/Vector3.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxCdrAux.hpp new file mode 100644 index 00000000000..cc925f190c9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaBoundingBoxCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOXCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOXCDRAUX_HPP_ + +#include "CarlaBoundingBox.h" + +constexpr uint32_t carla_msgs_msg_CarlaBoundingBox_max_cdr_typesize {64UL}; +constexpr uint32_t carla_msgs_msg_CarlaBoundingBox_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaBoundingBox& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOXCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxCdrAux.ipp new file mode 100644 index 00000000000..ee448481764 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaBoundingBoxCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOXCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOXCDRAUX_IPP_ + +#include "CarlaBoundingBoxCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaBoundingBox& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.center(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.size(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaBoundingBox& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.center() + << eprosima::fastcdr::MemberId(1) << data.size() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaBoundingBox& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.center(); + break; + + case 1: + dcdr >> data.size(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaBoundingBox& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOXCDRAUX_IPP_ + 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..416066fb334 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxPubSubTypes.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 CarlaBoundingBoxPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaBoundingBoxPubSubTypes.h" +#include "CarlaBoundingBoxCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaBoundingBoxPubSubType::CarlaBoundingBoxPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaBoundingBox_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaBoundingBox::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaBoundingBox_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaBoundingBoxPubSubType::~CarlaBoundingBoxPubSubType() +{ +} + +bool CarlaBoundingBoxPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaBoundingBoxPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaBoundingBoxPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..b8069ead4b9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaBoundingBoxPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaBoundingBox.h" + +#include "geometry_msgs/msg/Vector3PubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaBoundingBoxPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLABOUNDINGBOX_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.cxx new file mode 100644 index 00000000000..b140cd6d875 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.cxx @@ -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 CarlaCollisionEvent.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaCollisionEvent.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace carla_msgs { + +namespace msg { + + + +CarlaCollisionEvent::CarlaCollisionEvent() +{ +} + +CarlaCollisionEvent::~CarlaCollisionEvent() +{ +} + +CarlaCollisionEvent::CarlaCollisionEvent( + const CarlaCollisionEvent& x) +{ + m_header = x.m_header; + m_other_actor_id = x.m_other_actor_id; + m_normal_impulse = x.m_normal_impulse; +} + +CarlaCollisionEvent::CarlaCollisionEvent( + CarlaCollisionEvent&& x) noexcept +{ + 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); +} + +CarlaCollisionEvent& 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; + return *this; +} + +CarlaCollisionEvent& CarlaCollisionEvent::operator =( + CarlaCollisionEvent&& x) noexcept +{ + + 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); + return *this; +} + +bool 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); +} + +bool CarlaCollisionEvent::operator !=( + const CarlaCollisionEvent& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void CarlaCollisionEvent::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 CarlaCollisionEvent::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& CarlaCollisionEvent::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& 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 + */ +void CarlaCollisionEvent::other_actor_id( + uint32_t _other_actor_id) +{ + m_other_actor_id = _other_actor_id; +} + +/*! + * @brief This function returns the value of member other_actor_id + * @return Value of member other_actor_id + */ +uint32_t CarlaCollisionEvent::other_actor_id() const +{ + return m_other_actor_id; +} + +/*! + * @brief This function returns a reference to member other_actor_id + * @return Reference to member other_actor_id + */ +uint32_t& CarlaCollisionEvent::other_actor_id() +{ + return m_other_actor_id; +} + + +/*! + * @brief This function copies the value in member normal_impulse + * @param _normal_impulse New value to be copied in member normal_impulse + */ +void CarlaCollisionEvent::normal_impulse( + const geometry_msgs::msg::Vector3& _normal_impulse) +{ + m_normal_impulse = _normal_impulse; +} + +/*! + * @brief This function moves the value in member normal_impulse + * @param _normal_impulse New value to be moved in member normal_impulse + */ +void CarlaCollisionEvent::normal_impulse( + geometry_msgs::msg::Vector3&& _normal_impulse) +{ + m_normal_impulse = std::move(_normal_impulse); +} + +/*! + * @brief This function returns a constant reference to member normal_impulse + * @return Constant reference to member normal_impulse + */ +const geometry_msgs::msg::Vector3& CarlaCollisionEvent::normal_impulse() const +{ + return m_normal_impulse; +} + +/*! + * @brief This function returns a reference to member normal_impulse + * @return Reference to member normal_impulse + */ +geometry_msgs::msg::Vector3& CarlaCollisionEvent::normal_impulse() +{ + return m_normal_impulse; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaCollisionEventCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.h new file mode 100644 index 00000000000..f9d0cb25bad --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEvent.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 CarlaCollisionEvent.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "geometry_msgs/msg/Vector3.h" +#include "std_msgs/msg/Header.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(CARLACOLLISIONEVENT_SOURCE) +#define CARLACOLLISIONEVENT_DllAPI __declspec( dllexport ) +#else +#define CARLACOLLISIONEVENT_DllAPI __declspec( dllimport ) +#endif // CARLACOLLISIONEVENT_SOURCE +#else +#define CARLACOLLISIONEVENT_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLACOLLISIONEVENT_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure CarlaCollisionEvent defined by the user in the IDL file. + * @ingroup CarlaCollisionEvent + */ +class CarlaCollisionEvent +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaCollisionEvent(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaCollisionEvent(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaCollisionEvent that will be copied. + */ + eProsima_user_DllExport CarlaCollisionEvent( + const CarlaCollisionEvent& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaCollisionEvent that will be copied. + */ + eProsima_user_DllExport CarlaCollisionEvent( + CarlaCollisionEvent&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaCollisionEvent that will be copied. + */ + eProsima_user_DllExport CarlaCollisionEvent& operator =( + const CarlaCollisionEvent& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaCollisionEvent that will be copied. + */ + eProsima_user_DllExport CarlaCollisionEvent& operator =( + CarlaCollisionEvent&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaCollisionEvent object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaCollisionEvent& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaCollisionEvent object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaCollisionEvent& 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 other_actor_id + * @param _other_actor_id New value for member other_actor_id + */ + eProsima_user_DllExport void other_actor_id( + uint32_t _other_actor_id); + + /*! + * @brief This function returns the value of member other_actor_id + * @return Value of member other_actor_id + */ + eProsima_user_DllExport uint32_t other_actor_id() const; + + /*! + * @brief This function returns a reference to member other_actor_id + * @return Reference to member other_actor_id + */ + eProsima_user_DllExport uint32_t& other_actor_id(); + + + /*! + * @brief This function copies the value in member normal_impulse + * @param _normal_impulse New value to be copied in member normal_impulse + */ + eProsima_user_DllExport void normal_impulse( + const geometry_msgs::msg::Vector3& _normal_impulse); + + /*! + * @brief This function moves the value in member normal_impulse + * @param _normal_impulse New value to be moved in member normal_impulse + */ + eProsima_user_DllExport void normal_impulse( + geometry_msgs::msg::Vector3&& _normal_impulse); + + /*! + * @brief This function returns a constant reference to member normal_impulse + * @return Constant reference to member normal_impulse + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& normal_impulse() const; + + /*! + * @brief This function returns a reference to member normal_impulse + * @return Reference to member normal_impulse + */ + eProsima_user_DllExport geometry_msgs::msg::Vector3& normal_impulse(); + +private: + + std_msgs::msg::Header m_header; + uint32_t m_other_actor_id{0}; + geometry_msgs::msg::Vector3 m_normal_impulse; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventCdrAux.hpp new file mode 100644 index 00000000000..ea0a11cabcc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaCollisionEventCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENTCDRAUX_HPP_ + +#include "CarlaCollisionEvent.h" + +constexpr uint32_t carla_msgs_msg_CarlaCollisionEvent_max_cdr_typesize {312UL}; +constexpr uint32_t carla_msgs_msg_CarlaCollisionEvent_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaCollisionEvent& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventCdrAux.ipp new file mode 100644 index 00000000000..24c40acf1bb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaCollisionEventCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENTCDRAUX_IPP_ + +#include "CarlaCollisionEventCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaCollisionEvent& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.other_actor_id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.normal_impulse(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaCollisionEvent& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.other_actor_id() + << eprosima::fastcdr::MemberId(2) << data.normal_impulse() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaCollisionEvent& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.other_actor_id(); + break; + + case 2: + dcdr >> data.normal_impulse(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaCollisionEvent& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENTCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.cxx new file mode 100644 index 00000000000..05c03d31787 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.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 CarlaCollisionEventPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaCollisionEventPubSubTypes.h" +#include "CarlaCollisionEventCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaCollisionEventPubSubType::CarlaCollisionEventPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaCollisionEvent_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaCollisionEvent::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaCollisionEvent_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaCollisionEventPubSubType::~CarlaCollisionEventPubSubType() +{ +} + +bool CarlaCollisionEventPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CarlaCollisionEvent* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaCollisionEventPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaCollisionEventPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CarlaCollisionEventPubSubType::createData() +{ + return reinterpret_cast(new CarlaCollisionEvent()); +} + +void CarlaCollisionEventPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CarlaCollisionEventPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.h new file mode 100644 index 00000000000..f6f63562d43 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaCollisionEventPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaCollisionEventPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaCollisionEvent.h" + +#include "geometry_msgs/msg/Vector3PubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaCollisionEvent 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 CarlaCollisionEvent defined by the user in the IDL file. + * @ingroup CarlaCollisionEvent + */ +class CarlaCollisionEventPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaCollisionEvent type; + + eProsima_user_DllExport CarlaCollisionEventPubSubType(); + + eProsima_user_DllExport ~CarlaCollisionEventPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_PUBSUBTYPES_H_ + 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..db374c7d4fe --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControl.cxx @@ -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 CarlaControl.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + +namespace CarlaControl_Constants { + + +} // namespace CarlaControl_Constants + + +CarlaControl::CarlaControl() +{ +} + +CarlaControl::~CarlaControl() +{ +} + +CarlaControl::CarlaControl( + const CarlaControl& x) +{ + m_command = x.m_command; +} + +CarlaControl::CarlaControl( + CarlaControl&& x) noexcept +{ + m_command = x.m_command; +} + +CarlaControl& CarlaControl::operator =( + const CarlaControl& x) +{ + + m_command = x.m_command; + return *this; +} + +CarlaControl& CarlaControl::operator =( + CarlaControl&& x) noexcept +{ + + m_command = x.m_command; + return *this; +} + +bool CarlaControl::operator ==( + const CarlaControl& x) const +{ + return (m_command == x.m_command); +} + +bool CarlaControl::operator !=( + const CarlaControl& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member command + * @param _command New value for member command + */ +void CarlaControl::command( + int8_t _command) +{ + m_command = _command; +} + +/*! + * @brief This function returns the value of member command + * @return Value of member command + */ +int8_t CarlaControl::command() const +{ + return m_command; +} + +/*! + * @brief This function returns a reference to member command + * @return Reference to member command + */ +int8_t& CarlaControl::command() +{ + return m_command; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaControlCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControl.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControl.h new file mode 100644 index 00000000000..8cebc790c8f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControl.h @@ -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 CarlaControl.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_H_ + +#include +#include +#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(CARLACONTROL_SOURCE) +#define CARLACONTROL_DllAPI __declspec( dllexport ) +#else +#define CARLACONTROL_DllAPI __declspec( dllimport ) +#endif // CARLACONTROL_SOURCE +#else +#define CARLACONTROL_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLACONTROL_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +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 CarlaControl defined by the user in the IDL file. + * @ingroup CarlaControl + */ +class CarlaControl +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaControl(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaControl(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaControl that will be copied. + */ + eProsima_user_DllExport CarlaControl( + const CarlaControl& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaControl that will be copied. + */ + eProsima_user_DllExport CarlaControl( + CarlaControl&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaControl that will be copied. + */ + eProsima_user_DllExport CarlaControl& operator =( + const CarlaControl& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaControl that will be copied. + */ + eProsima_user_DllExport CarlaControl& operator =( + CarlaControl&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaControl object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaControl& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaControl object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaControl& x) const; + + /*! + * @brief This function sets a value in member command + * @param _command New value for member command + */ + eProsima_user_DllExport void command( + int8_t _command); + + /*! + * @brief This function returns the value of member command + * @return Value of member command + */ + eProsima_user_DllExport int8_t command() const; + + /*! + * @brief This function returns a reference to member command + * @return Reference to member command + */ + eProsima_user_DllExport int8_t& command(); + +private: + + int8_t m_command{0}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlCdrAux.hpp new file mode 100644 index 00000000000..dd35e545336 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaControlCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROLCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROLCDRAUX_HPP_ + +#include "CarlaControl.h" + +constexpr uint32_t carla_msgs_msg_CarlaControl_max_cdr_typesize {5UL}; +constexpr uint32_t carla_msgs_msg_CarlaControl_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaControl& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROLCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlCdrAux.ipp new file mode 100644 index 00000000000..d15f5134b95 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaControlCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROLCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROLCDRAUX_IPP_ + +#include "CarlaControlCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaControl& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.command(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaControl& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.command() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaControl& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.command(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaControl& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROLCDRAUX_IPP_ + 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..4f57db4bb82 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlPubSubTypes.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 CarlaControlPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaControlPubSubTypes.h" +#include "CarlaControlCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { +namespace CarlaControl_Constants { + + + + + + + +} //End of namespace CarlaControl_Constants + + + +CarlaControlPubSubType::CarlaControlPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaControl_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaControl::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaControl_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaControlPubSubType::~CarlaControlPubSubType() +{ +} + +bool CarlaControlPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaControlPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaControlPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..12db88d0c4f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaControlPubSubTypes.h @@ -0,0 +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 CarlaControlPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaControl.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + +} // 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 ~CarlaControlPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACONTROL_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControl.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControl.cxx new file mode 100644 index 00000000000..2172ffd97bb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControl.cxx @@ -0,0 +1,413 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleControl.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaEgoVehicleControl.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace carla_msgs { + +namespace msg { + + + +CarlaEgoVehicleControl::CarlaEgoVehicleControl() +{ +} + +CarlaEgoVehicleControl::~CarlaEgoVehicleControl() +{ +} + +CarlaEgoVehicleControl::CarlaEgoVehicleControl( + const CarlaEgoVehicleControl& x) +{ + 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; +} + +CarlaEgoVehicleControl::CarlaEgoVehicleControl( + CarlaEgoVehicleControl&& x) noexcept +{ + m_header = std::move(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; +} + +CarlaEgoVehicleControl& CarlaEgoVehicleControl::operator =( + const CarlaEgoVehicleControl& x) +{ + + 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; + return *this; +} + +CarlaEgoVehicleControl& CarlaEgoVehicleControl::operator =( + CarlaEgoVehicleControl&& x) noexcept +{ + + m_header = std::move(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; + return *this; +} + +bool CarlaEgoVehicleControl::operator ==( + const CarlaEgoVehicleControl& 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 && + m_control_priority == x.m_control_priority); +} + +bool CarlaEgoVehicleControl::operator !=( + const CarlaEgoVehicleControl& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void CarlaEgoVehicleControl::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 CarlaEgoVehicleControl::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& CarlaEgoVehicleControl::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& CarlaEgoVehicleControl::header() +{ + return m_header; +} + + +/*! + * @brief This function sets a value in member throttle + * @param _throttle New value for member throttle + */ +void CarlaEgoVehicleControl::throttle( + float _throttle) +{ + m_throttle = _throttle; +} + +/*! + * @brief This function returns the value of member throttle + * @return Value of member throttle + */ +float CarlaEgoVehicleControl::throttle() const +{ + return m_throttle; +} + +/*! + * @brief This function returns a reference to member throttle + * @return Reference to member throttle + */ +float& CarlaEgoVehicleControl::throttle() +{ + return m_throttle; +} + + +/*! + * @brief This function sets a value in member steer + * @param _steer New value for member steer + */ +void CarlaEgoVehicleControl::steer( + float _steer) +{ + m_steer = _steer; +} + +/*! + * @brief This function returns the value of member steer + * @return Value of member steer + */ +float CarlaEgoVehicleControl::steer() const +{ + return m_steer; +} + +/*! + * @brief This function returns a reference to member steer + * @return Reference to member steer + */ +float& CarlaEgoVehicleControl::steer() +{ + return m_steer; +} + + +/*! + * @brief This function sets a value in member brake + * @param _brake New value for member brake + */ +void CarlaEgoVehicleControl::brake( + float _brake) +{ + m_brake = _brake; +} + +/*! + * @brief This function returns the value of member brake + * @return Value of member brake + */ +float CarlaEgoVehicleControl::brake() const +{ + return m_brake; +} + +/*! + * @brief This function returns a reference to member brake + * @return Reference to member brake + */ +float& CarlaEgoVehicleControl::brake() +{ + return m_brake; +} + + +/*! + * @brief This function sets a value in member hand_brake + * @param _hand_brake New value for member hand_brake + */ +void CarlaEgoVehicleControl::hand_brake( + bool _hand_brake) +{ + m_hand_brake = _hand_brake; +} + +/*! + * @brief This function returns the value of member hand_brake + * @return Value of member hand_brake + */ +bool CarlaEgoVehicleControl::hand_brake() const +{ + return m_hand_brake; +} + +/*! + * @brief This function returns a reference to member hand_brake + * @return Reference to member hand_brake + */ +bool& CarlaEgoVehicleControl::hand_brake() +{ + return m_hand_brake; +} + + +/*! + * @brief This function sets a value in member reverse + * @param _reverse New value for member reverse + */ +void CarlaEgoVehicleControl::reverse( + bool _reverse) +{ + m_reverse = _reverse; +} + +/*! + * @brief This function returns the value of member reverse + * @return Value of member reverse + */ +bool CarlaEgoVehicleControl::reverse() const +{ + return m_reverse; +} + +/*! + * @brief This function returns a reference to member reverse + * @return Reference to member reverse + */ +bool& CarlaEgoVehicleControl::reverse() +{ + return m_reverse; +} + + +/*! + * @brief This function sets a value in member gear + * @param _gear New value for member gear + */ +void CarlaEgoVehicleControl::gear( + int32_t _gear) +{ + m_gear = _gear; +} + +/*! + * @brief This function returns the value of member gear + * @return Value of member gear + */ +int32_t CarlaEgoVehicleControl::gear() const +{ + return m_gear; +} + +/*! + * @brief This function returns a reference to member gear + * @return Reference to member gear + */ +int32_t& CarlaEgoVehicleControl::gear() +{ + return m_gear; +} + + +/*! + * @brief This function sets a value in member manual_gear_shift + * @param _manual_gear_shift New value for member manual_gear_shift + */ +void CarlaEgoVehicleControl::manual_gear_shift( + bool _manual_gear_shift) +{ + m_manual_gear_shift = _manual_gear_shift; +} + +/*! + * @brief This function returns the value of member manual_gear_shift + * @return Value of member manual_gear_shift + */ +bool CarlaEgoVehicleControl::manual_gear_shift() const +{ + return m_manual_gear_shift; +} + +/*! + * @brief This function returns a reference to member manual_gear_shift + * @return Reference to member manual_gear_shift + */ +bool& CarlaEgoVehicleControl::manual_gear_shift() +{ + return m_manual_gear_shift; +} + + +/*! + * @brief This function sets a value in member control_priority + * @param _control_priority New value for member control_priority + */ +void CarlaEgoVehicleControl::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 CarlaEgoVehicleControl::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& CarlaEgoVehicleControl::control_priority() +{ + return m_control_priority; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaEgoVehicleControlCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControl.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControl.h new file mode 100644 index 00000000000..a8566142681 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControl.h @@ -0,0 +1,345 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleControl.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROL_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROL_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "std_msgs/msg/Header.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(CARLAEGOVEHICLECONTROL_SOURCE) +#define CARLAEGOVEHICLECONTROL_DllAPI __declspec( dllexport ) +#else +#define CARLAEGOVEHICLECONTROL_DllAPI __declspec( dllimport ) +#endif // CARLAEGOVEHICLECONTROL_SOURCE +#else +#define CARLAEGOVEHICLECONTROL_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLAEGOVEHICLECONTROL_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // 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 + */ +class CarlaEgoVehicleControl +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaEgoVehicleControl(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaEgoVehicleControl(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleControl( + const CarlaEgoVehicleControl& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleControl( + CarlaEgoVehicleControl&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleControl& operator =( + const CarlaEgoVehicleControl& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleControl& operator =( + CarlaEgoVehicleControl&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleControl object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaEgoVehicleControl& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleControl object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaEgoVehicleControl& 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 throttle + * @param _throttle New value for member throttle + */ + eProsima_user_DllExport void throttle( + float _throttle); + + /*! + * @brief This function returns the value of member throttle + * @return Value of member throttle + */ + eProsima_user_DllExport float throttle() const; + + /*! + * @brief This function returns a reference to member throttle + * @return Reference to member throttle + */ + eProsima_user_DllExport float& throttle(); + + + /*! + * @brief This function sets a value in member steer + * @param _steer New value for member steer + */ + eProsima_user_DllExport void steer( + float _steer); + + /*! + * @brief This function returns the value of member steer + * @return Value of member steer + */ + eProsima_user_DllExport float steer() const; + + /*! + * @brief This function returns a reference to member steer + * @return Reference to member steer + */ + eProsima_user_DllExport float& steer(); + + + /*! + * @brief This function sets a value in member brake + * @param _brake New value for member brake + */ + eProsima_user_DllExport void brake( + float _brake); + + /*! + * @brief This function returns the value of member brake + * @return Value of member brake + */ + eProsima_user_DllExport float brake() const; + + /*! + * @brief This function returns a reference to member brake + * @return Reference to member brake + */ + eProsima_user_DllExport float& brake(); + + + /*! + * @brief This function sets a value in member hand_brake + * @param _hand_brake New value for member hand_brake + */ + eProsima_user_DllExport void hand_brake( + bool _hand_brake); + + /*! + * @brief This function returns the value of member hand_brake + * @return Value of member hand_brake + */ + eProsima_user_DllExport bool hand_brake() const; + + /*! + * @brief This function returns a reference to member hand_brake + * @return Reference to member hand_brake + */ + eProsima_user_DllExport bool& hand_brake(); + + + /*! + * @brief This function sets a value in member reverse + * @param _reverse New value for member reverse + */ + eProsima_user_DllExport void reverse( + bool _reverse); + + /*! + * @brief This function returns the value of member reverse + * @return Value of member reverse + */ + eProsima_user_DllExport bool reverse() const; + + /*! + * @brief This function returns a reference to member reverse + * @return Reference to member reverse + */ + eProsima_user_DllExport bool& reverse(); + + + /*! + * @brief This function sets a value in member gear + * @param _gear New value for member gear + */ + eProsima_user_DllExport void gear( + int32_t _gear); + + /*! + * @brief This function returns the value of member gear + * @return Value of member gear + */ + eProsima_user_DllExport int32_t gear() const; + + /*! + * @brief This function returns a reference to member gear + * @return Reference to member gear + */ + eProsima_user_DllExport int32_t& gear(); + + + /*! + * @brief This function sets a value in member manual_gear_shift + * @param _manual_gear_shift New value for member manual_gear_shift + */ + eProsima_user_DllExport void manual_gear_shift( + bool _manual_gear_shift); + + /*! + * @brief This function returns the value of member manual_gear_shift + * @return Value of member manual_gear_shift + */ + eProsima_user_DllExport bool manual_gear_shift() const; + + /*! + * @brief This function returns a reference to member manual_gear_shift + * @return Reference to member manual_gear_shift + */ + eProsima_user_DllExport bool& manual_gear_shift(); + + + /*! + * @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(); + +private: + + std_msgs::msg::Header m_header; + float m_throttle{0.0}; + float m_steer{0.0}; + float m_brake{0.0}; + bool m_hand_brake{false}; + bool m_reverse{false}; + int32_t m_gear{0}; + bool m_manual_gear_shift{false}; + uint8_t m_control_priority{4}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROL_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlCdrAux.hpp new file mode 100644 index 00000000000..defee7b76b2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleControlCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROLCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROLCDRAUX_HPP_ + +#include "CarlaEgoVehicleControl.h" + +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleControl_max_cdr_typesize {302UL}; +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleControl_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleControl& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROLCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlCdrAux.ipp new file mode 100644 index 00000000000..f7c24e9d882 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlCdrAux.ipp @@ -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 CarlaEgoVehicleControlCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROLCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROLCDRAUX_IPP_ + +#include "CarlaEgoVehicleControlCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaEgoVehicleControl& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.throttle(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.steer(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.brake(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.hand_brake(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.reverse(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.gear(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.manual_gear_shift(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.control_priority(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleControl& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.throttle() + << eprosima::fastcdr::MemberId(2) << data.steer() + << eprosima::fastcdr::MemberId(3) << data.brake() + << eprosima::fastcdr::MemberId(4) << data.hand_brake() + << eprosima::fastcdr::MemberId(5) << data.reverse() + << eprosima::fastcdr::MemberId(6) << data.gear() + << eprosima::fastcdr::MemberId(7) << data.manual_gear_shift() + << eprosima::fastcdr::MemberId(8) << data.control_priority() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaEgoVehicleControl& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.throttle(); + break; + + case 2: + dcdr >> data.steer(); + break; + + case 3: + dcdr >> data.brake(); + break; + + case 4: + dcdr >> data.hand_brake(); + break; + + case 5: + dcdr >> data.reverse(); + break; + + case 6: + dcdr >> data.gear(); + break; + + case 7: + dcdr >> data.manual_gear_shift(); + break; + + case 8: + dcdr >> data.control_priority(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleControl& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROLCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlPubSubTypes.cxx new file mode 100644 index 00000000000..2d1caed9195 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlPubSubTypes.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 CarlaEgoVehicleControlPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaEgoVehicleControlPubSubTypes.h" +#include "CarlaEgoVehicleControlCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaEgoVehicleControlPubSubType::CarlaEgoVehicleControlPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaEgoVehicleControl_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaEgoVehicleControl::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaEgoVehicleControl_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaEgoVehicleControlPubSubType::~CarlaEgoVehicleControlPubSubType() +{ +} + +bool CarlaEgoVehicleControlPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CarlaEgoVehicleControl* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaEgoVehicleControlPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + CarlaEgoVehicleControl* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaEgoVehicleControlPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CarlaEgoVehicleControlPubSubType::createData() +{ + return reinterpret_cast(new CarlaEgoVehicleControl()); +} + +void CarlaEgoVehicleControlPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CarlaEgoVehicleControlPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlPubSubTypes.h new file mode 100644 index 00000000000..f8dc4a6f9c7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleControlPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleControlPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROL_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaEgoVehicleControl.h" + +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaEgoVehicleControl 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 CarlaEgoVehicleControl defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleControl + */ +class CarlaEgoVehicleControlPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaEgoVehicleControl type; + + eProsima_user_DllExport CarlaEgoVehicleControlPubSubType(); + + eProsima_user_DllExport ~CarlaEgoVehicleControlPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLECONTROL_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfo.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfo.cxx new file mode 100644 index 00000000000..e7156271efb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfo.cxx @@ -0,0 +1,647 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleInfo.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaEgoVehicleInfo.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace carla_msgs { + +namespace msg { + + + +CarlaEgoVehicleInfo::CarlaEgoVehicleInfo() +{ +} + +CarlaEgoVehicleInfo::~CarlaEgoVehicleInfo() +{ +} + +CarlaEgoVehicleInfo::CarlaEgoVehicleInfo( + const CarlaEgoVehicleInfo& 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; +} + +CarlaEgoVehicleInfo::CarlaEgoVehicleInfo( + CarlaEgoVehicleInfo&& x) noexcept +{ + 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); +} + +CarlaEgoVehicleInfo& CarlaEgoVehicleInfo::operator =( + const CarlaEgoVehicleInfo& 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; + return *this; +} + +CarlaEgoVehicleInfo& CarlaEgoVehicleInfo::operator =( + CarlaEgoVehicleInfo&& x) noexcept +{ + + 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); + return *this; +} + +bool CarlaEgoVehicleInfo::operator ==( + const CarlaEgoVehicleInfo& 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); +} + +bool CarlaEgoVehicleInfo::operator !=( + const CarlaEgoVehicleInfo& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void CarlaEgoVehicleInfo::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t CarlaEgoVehicleInfo::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& CarlaEgoVehicleInfo::id() +{ + return m_id; +} + + +/*! + * @brief This function copies the value in member type + * @param _type New value to be copied in member type + */ +void CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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& CarlaEgoVehicleInfo::type() const +{ + return m_type; +} + +/*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ +std::string& CarlaEgoVehicleInfo::type() +{ + return m_type; +} + + +/*! + * @brief This function copies the value in member rolename + * @param _rolename New value to be copied in member rolename + */ +void CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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& CarlaEgoVehicleInfo::rolename() const +{ + return m_rolename; +} + +/*! + * @brief This function returns a reference to member rolename + * @return Reference to member rolename + */ +std::string& CarlaEgoVehicleInfo::rolename() +{ + return m_rolename; +} + + +/*! + * @brief This function copies the value in member wheels + * @param _wheels New value to be copied in member wheels + */ +void CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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& CarlaEgoVehicleInfo::wheels() const +{ + return m_wheels; +} + +/*! + * @brief This function returns a reference to member wheels + * @return Reference to member wheels + */ +std::vector& CarlaEgoVehicleInfo::wheels() +{ + return m_wheels; +} + + +/*! + * @brief This function sets a value in member max_rpm + * @param _max_rpm New value for member max_rpm + */ +void CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::max_rpm() const +{ + return m_max_rpm; +} + +/*! + * @brief This function returns a reference to member max_rpm + * @return Reference to member max_rpm + */ +float& CarlaEgoVehicleInfo::max_rpm() +{ + return m_max_rpm; +} + + +/*! + * @brief This function sets a value in member moi + * @param _moi New value for member moi + */ +void CarlaEgoVehicleInfo::moi( + float _moi) +{ + m_moi = _moi; +} + +/*! + * @brief This function returns the value of member moi + * @return Value of member moi + */ +float CarlaEgoVehicleInfo::moi() const +{ + return m_moi; +} + +/*! + * @brief This function returns a reference to member moi + * @return Reference to member moi + */ +float& CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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& CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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& CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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& CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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& CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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& CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::clutch_strength() const +{ + return m_clutch_strength; +} + +/*! + * @brief This function returns a reference to member clutch_strength + * @return Reference to member clutch_strength + */ +float& CarlaEgoVehicleInfo::clutch_strength() +{ + return m_clutch_strength; +} + + +/*! + * @brief This function sets a value in member mass + * @param _mass New value for member mass + */ +void CarlaEgoVehicleInfo::mass( + float _mass) +{ + m_mass = _mass; +} + +/*! + * @brief This function returns the value of member mass + * @return Value of member mass + */ +float CarlaEgoVehicleInfo::mass() const +{ + return m_mass; +} + +/*! + * @brief This function returns a reference to member mass + * @return Reference to member mass + */ +float& CarlaEgoVehicleInfo::mass() +{ + return m_mass; +} + + +/*! + * @brief This function sets a value in member drag_coefficient + * @param _drag_coefficient New value for member drag_coefficient + */ +void CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::drag_coefficient() const +{ + return m_drag_coefficient; +} + +/*! + * @brief This function returns a reference to member drag_coefficient + * @return Reference to member drag_coefficient + */ +float& CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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 CarlaEgoVehicleInfo::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& CarlaEgoVehicleInfo::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& CarlaEgoVehicleInfo::center_of_mass() +{ + return m_center_of_mass; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaEgoVehicleInfoCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfo.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfo.h new file mode 100644 index 00000000000..5f83d903766 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfo.h @@ -0,0 +1,492 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleInfo.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFO_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFO_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CarlaEgoVehicleInfoWheel.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(CARLAEGOVEHICLEINFO_SOURCE) +#define CARLAEGOVEHICLEINFO_DllAPI __declspec( dllexport ) +#else +#define CARLAEGOVEHICLEINFO_DllAPI __declspec( dllimport ) +#endif // CARLAEGOVEHICLEINFO_SOURCE +#else +#define CARLAEGOVEHICLEINFO_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLAEGOVEHICLEINFO_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure CarlaEgoVehicleInfo defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleInfo + */ +class CarlaEgoVehicleInfo +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaEgoVehicleInfo(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaEgoVehicleInfo(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleInfo that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleInfo( + const CarlaEgoVehicleInfo& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleInfo that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleInfo( + CarlaEgoVehicleInfo&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleInfo that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleInfo& operator =( + const CarlaEgoVehicleInfo& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleInfo that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleInfo& operator =( + CarlaEgoVehicleInfo&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleInfo object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaEgoVehicleInfo& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleInfo object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaEgoVehicleInfo& 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(); + +private: + + uint32_t m_id{0}; + std::string m_type; + std::string m_rolename; + std::vector m_wheels; + float m_max_rpm{0.0}; + float m_moi{0.0}; + float m_damping_rate_full_throttle{0.0}; + float m_damping_rate_zero_throttle_clutch_engaged{0.0}; + float m_damping_rate_zero_throttle_clutch_disengaged{0.0}; + bool m_use_gear_autobox{false}; + float m_gear_switch_time{0.0}; + float m_clutch_strength{0.0}; + float m_mass{0.0}; + float m_drag_coefficient{0.0}; + geometry_msgs::msg::Vector3 m_center_of_mass; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFO_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoCdrAux.hpp new file mode 100644 index 00000000000..747b4b85d84 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleInfoCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOCDRAUX_HPP_ + +#include "CarlaEgoVehicleInfo.h" + +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleInfo_max_cdr_typesize {6208UL}; +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleInfo_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleInfo& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoCdrAux.ipp new file mode 100644 index 00000000000..0a3ac70d324 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoCdrAux.ipp @@ -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 CarlaEgoVehicleInfoCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOCDRAUX_IPP_ + +#include "CarlaEgoVehicleInfoCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaEgoVehicleInfo& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.rolename(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.wheels(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.max_rpm(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.moi(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.damping_rate_full_throttle(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.damping_rate_zero_throttle_clutch_engaged(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.damping_rate_zero_throttle_clutch_disengaged(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), + data.use_gear_autobox(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(10), + data.gear_switch_time(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(11), + data.clutch_strength(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(12), + data.mass(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(13), + data.drag_coefficient(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(14), + data.center_of_mass(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleInfo& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.id() + << eprosima::fastcdr::MemberId(1) << data.type() + << eprosima::fastcdr::MemberId(2) << data.rolename() + << eprosima::fastcdr::MemberId(3) << data.wheels() + << eprosima::fastcdr::MemberId(4) << data.max_rpm() + << eprosima::fastcdr::MemberId(5) << data.moi() + << eprosima::fastcdr::MemberId(6) << data.damping_rate_full_throttle() + << eprosima::fastcdr::MemberId(7) << data.damping_rate_zero_throttle_clutch_engaged() + << eprosima::fastcdr::MemberId(8) << data.damping_rate_zero_throttle_clutch_disengaged() + << eprosima::fastcdr::MemberId(9) << data.use_gear_autobox() + << eprosima::fastcdr::MemberId(10) << data.gear_switch_time() + << eprosima::fastcdr::MemberId(11) << data.clutch_strength() + << eprosima::fastcdr::MemberId(12) << data.mass() + << eprosima::fastcdr::MemberId(13) << data.drag_coefficient() + << eprosima::fastcdr::MemberId(14) << data.center_of_mass() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaEgoVehicleInfo& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.id(); + break; + + case 1: + dcdr >> data.type(); + break; + + case 2: + dcdr >> data.rolename(); + break; + + case 3: + dcdr >> data.wheels(); + break; + + case 4: + dcdr >> data.max_rpm(); + break; + + case 5: + dcdr >> data.moi(); + break; + + case 6: + dcdr >> data.damping_rate_full_throttle(); + break; + + case 7: + dcdr >> data.damping_rate_zero_throttle_clutch_engaged(); + break; + + case 8: + dcdr >> data.damping_rate_zero_throttle_clutch_disengaged(); + break; + + case 9: + dcdr >> data.use_gear_autobox(); + break; + + case 10: + dcdr >> data.gear_switch_time(); + break; + + case 11: + dcdr >> data.clutch_strength(); + break; + + case 12: + dcdr >> data.mass(); + break; + + case 13: + dcdr >> data.drag_coefficient(); + break; + + case 14: + dcdr >> data.center_of_mass(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleInfo& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoPubSubTypes.cxx new file mode 100644 index 00000000000..9f2b65c43cd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoPubSubTypes.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 CarlaEgoVehicleInfoPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaEgoVehicleInfoPubSubTypes.h" +#include "CarlaEgoVehicleInfoCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaEgoVehicleInfoPubSubType::CarlaEgoVehicleInfoPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaEgoVehicleInfo_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaEgoVehicleInfo::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaEgoVehicleInfo_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaEgoVehicleInfoPubSubType::~CarlaEgoVehicleInfoPubSubType() +{ +} + +bool CarlaEgoVehicleInfoPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CarlaEgoVehicleInfo* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaEgoVehicleInfoPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + CarlaEgoVehicleInfo* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaEgoVehicleInfoPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CarlaEgoVehicleInfoPubSubType::createData() +{ + return reinterpret_cast(new CarlaEgoVehicleInfo()); +} + +void CarlaEgoVehicleInfoPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CarlaEgoVehicleInfoPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoPubSubTypes.h new file mode 100644 index 00000000000..d7351a905f4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleInfoPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFO_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFO_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaEgoVehicleInfo.h" + +#include "CarlaEgoVehicleInfoWheelPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaEgoVehicleInfo 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 CarlaEgoVehicleInfo defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleInfo + */ +class CarlaEgoVehicleInfoPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaEgoVehicleInfo type; + + eProsima_user_DllExport CarlaEgoVehicleInfoPubSubType(); + + eProsima_user_DllExport ~CarlaEgoVehicleInfoPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFO_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheel.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheel.cxx new file mode 100644 index 00000000000..8c6d5ad56b8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheel.cxx @@ -0,0 +1,345 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleInfoWheel.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaEgoVehicleInfoWheel.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace carla_msgs { + +namespace msg { + + + +CarlaEgoVehicleInfoWheel::CarlaEgoVehicleInfoWheel() +{ +} + +CarlaEgoVehicleInfoWheel::~CarlaEgoVehicleInfoWheel() +{ +} + +CarlaEgoVehicleInfoWheel::CarlaEgoVehicleInfoWheel( + const CarlaEgoVehicleInfoWheel& 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; +} + +CarlaEgoVehicleInfoWheel::CarlaEgoVehicleInfoWheel( + CarlaEgoVehicleInfoWheel&& x) noexcept +{ + 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); +} + +CarlaEgoVehicleInfoWheel& CarlaEgoVehicleInfoWheel::operator =( + const CarlaEgoVehicleInfoWheel& 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; +} + +CarlaEgoVehicleInfoWheel& CarlaEgoVehicleInfoWheel::operator =( + CarlaEgoVehicleInfoWheel&& x) noexcept +{ + + 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 CarlaEgoVehicleInfoWheel::operator ==( + const CarlaEgoVehicleInfoWheel& 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 CarlaEgoVehicleInfoWheel::operator !=( + const CarlaEgoVehicleInfoWheel& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member tire_friction + * @param _tire_friction New value for member tire_friction + */ +void CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::tire_friction() const +{ + return m_tire_friction; +} + +/*! + * @brief This function returns a reference to member tire_friction + * @return Reference to member tire_friction + */ +float& CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::damping_rate() const +{ + return m_damping_rate; +} + +/*! + * @brief This function returns a reference to member damping_rate + * @return Reference to member damping_rate + */ +float& CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::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& CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::radius( + float _radius) +{ + m_radius = _radius; +} + +/*! + * @brief This function returns the value of member radius + * @return Value of member radius + */ +float CarlaEgoVehicleInfoWheel::radius() const +{ + return m_radius; +} + +/*! + * @brief This function returns a reference to member radius + * @return Reference to member radius + */ +float& CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::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& CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::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& CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::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 CarlaEgoVehicleInfoWheel::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& CarlaEgoVehicleInfoWheel::position() const +{ + return m_position; +} + +/*! + * @brief This function returns a reference to member position + * @return Reference to member position + */ +geometry_msgs::msg::Vector3& CarlaEgoVehicleInfoWheel::position() +{ + return m_position; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaEgoVehicleInfoWheelCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheel.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheel.h new file mode 100644 index 00000000000..28533b81983 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheel.h @@ -0,0 +1,303 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleInfoWheel.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEEL_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEEL_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "geometry_msgs/msg/Vector3.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(CARLAEGOVEHICLEINFOWHEEL_SOURCE) +#define CARLAEGOVEHICLEINFOWHEEL_DllAPI __declspec( dllexport ) +#else +#define CARLAEGOVEHICLEINFOWHEEL_DllAPI __declspec( dllimport ) +#endif // CARLAEGOVEHICLEINFOWHEEL_SOURCE +#else +#define CARLAEGOVEHICLEINFOWHEEL_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLAEGOVEHICLEINFOWHEEL_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure CarlaEgoVehicleInfoWheel defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleInfoWheel + */ +class CarlaEgoVehicleInfoWheel +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaEgoVehicleInfoWheel(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaEgoVehicleInfoWheel(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleInfoWheel that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleInfoWheel( + const CarlaEgoVehicleInfoWheel& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleInfoWheel that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleInfoWheel( + CarlaEgoVehicleInfoWheel&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleInfoWheel that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleInfoWheel& operator =( + const CarlaEgoVehicleInfoWheel& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleInfoWheel that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleInfoWheel& operator =( + CarlaEgoVehicleInfoWheel&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleInfoWheel object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaEgoVehicleInfoWheel& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleInfoWheel object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaEgoVehicleInfoWheel& 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(); + +private: + + float m_tire_friction{0.0}; + float m_damping_rate{0.0}; + float m_max_steer_angle{0.0}; + float m_radius{0.0}; + float m_max_brake_torque{0.0}; + float m_max_handbrake_torque{0.0}; + geometry_msgs::msg::Vector3 m_position; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEEL_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelCdrAux.hpp new file mode 100644 index 00000000000..17e7dc497ba --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleInfoWheelCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEELCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEELCDRAUX_HPP_ + +#include "CarlaEgoVehicleInfoWheel.h" + +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleInfoWheel_max_cdr_typesize {56UL}; +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleInfoWheel_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleInfoWheel& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEELCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelCdrAux.ipp new file mode 100644 index 00000000000..687b6908eff --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelCdrAux.ipp @@ -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 CarlaEgoVehicleInfoWheelCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEELCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEELCDRAUX_IPP_ + +#include "CarlaEgoVehicleInfoWheelCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaEgoVehicleInfoWheel& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.tire_friction(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.damping_rate(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.max_steer_angle(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.radius(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.max_brake_torque(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.max_handbrake_torque(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.position(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleInfoWheel& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.tire_friction() + << eprosima::fastcdr::MemberId(1) << data.damping_rate() + << eprosima::fastcdr::MemberId(2) << data.max_steer_angle() + << eprosima::fastcdr::MemberId(3) << data.radius() + << eprosima::fastcdr::MemberId(4) << data.max_brake_torque() + << eprosima::fastcdr::MemberId(5) << data.max_handbrake_torque() + << eprosima::fastcdr::MemberId(6) << data.position() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaEgoVehicleInfoWheel& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.tire_friction(); + break; + + case 1: + dcdr >> data.damping_rate(); + break; + + case 2: + dcdr >> data.max_steer_angle(); + break; + + case 3: + dcdr >> data.radius(); + break; + + case 4: + dcdr >> data.max_brake_torque(); + break; + + case 5: + dcdr >> data.max_handbrake_torque(); + break; + + case 6: + dcdr >> data.position(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleInfoWheel& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEELCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelPubSubTypes.cxx new file mode 100644 index 00000000000..7053a6b4126 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelPubSubTypes.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 CarlaEgoVehicleInfoWheelPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaEgoVehicleInfoWheelPubSubTypes.h" +#include "CarlaEgoVehicleInfoWheelCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaEgoVehicleInfoWheelPubSubType::CarlaEgoVehicleInfoWheelPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaEgoVehicleInfoWheel_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaEgoVehicleInfoWheel::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaEgoVehicleInfoWheel_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaEgoVehicleInfoWheelPubSubType::~CarlaEgoVehicleInfoWheelPubSubType() +{ +} + +bool CarlaEgoVehicleInfoWheelPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CarlaEgoVehicleInfoWheel* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaEgoVehicleInfoWheelPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + CarlaEgoVehicleInfoWheel* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaEgoVehicleInfoWheelPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CarlaEgoVehicleInfoWheelPubSubType::createData() +{ + return reinterpret_cast(new CarlaEgoVehicleInfoWheel()); +} + +void CarlaEgoVehicleInfoWheelPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CarlaEgoVehicleInfoWheelPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelPubSubTypes.h new file mode 100644 index 00000000000..68a6d8f992c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleInfoWheelPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleInfoWheelPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEEL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEEL_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaEgoVehicleInfoWheel.h" + +#include "geometry_msgs/msg/Vector3PubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaEgoVehicleInfoWheel 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 CarlaEgoVehicleInfoWheel defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleInfoWheel + */ +class CarlaEgoVehicleInfoWheelPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaEgoVehicleInfoWheel type; + + eProsima_user_DllExport CarlaEgoVehicleInfoWheelPubSubType(); + + eProsima_user_DllExport ~CarlaEgoVehicleInfoWheelPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLEINFOWHEEL_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatus.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatus.cxx new file mode 100644 index 00000000000..a48b2704480 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatus.cxx @@ -0,0 +1,389 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleStatus.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaEgoVehicleStatus.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace carla_msgs { + +namespace msg { + +namespace CarlaEgoVehicleStatus_Constants { + + +} // namespace CarlaEgoVehicleStatus_Constants + + +CarlaEgoVehicleStatus::CarlaEgoVehicleStatus() +{ +} + +CarlaEgoVehicleStatus::~CarlaEgoVehicleStatus() +{ +} + +CarlaEgoVehicleStatus::CarlaEgoVehicleStatus( + const CarlaEgoVehicleStatus& x) +{ + m_header = x.m_header; + m_velocity = x.m_velocity; + m_acceleration = x.m_acceleration; + m_orientation = x.m_orientation; + 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; +} + +CarlaEgoVehicleStatus::CarlaEgoVehicleStatus( + CarlaEgoVehicleStatus&& x) noexcept +{ + m_header = std::move(x.m_header); + m_velocity = x.m_velocity; + m_acceleration = std::move(x.m_acceleration); + m_orientation = std::move(x.m_orientation); + 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); +} + +CarlaEgoVehicleStatus& CarlaEgoVehicleStatus::operator =( + const CarlaEgoVehicleStatus& x) +{ + + m_header = x.m_header; + m_velocity = x.m_velocity; + m_acceleration = x.m_acceleration; + m_orientation = x.m_orientation; + 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; +} + +CarlaEgoVehicleStatus& CarlaEgoVehicleStatus::operator =( + CarlaEgoVehicleStatus&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_velocity = x.m_velocity; + m_acceleration = std::move(x.m_acceleration); + m_orientation = std::move(x.m_orientation); + 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 CarlaEgoVehicleStatus::operator ==( + const CarlaEgoVehicleStatus& x) const +{ + return (m_header == x.m_header && + m_velocity == x.m_velocity && + m_acceleration == x.m_acceleration && + m_orientation == x.m_orientation && + 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 CarlaEgoVehicleStatus::operator !=( + const CarlaEgoVehicleStatus& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void CarlaEgoVehicleStatus::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 CarlaEgoVehicleStatus::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& CarlaEgoVehicleStatus::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& CarlaEgoVehicleStatus::header() +{ + return m_header; +} + + +/*! + * @brief This function sets a value in member velocity + * @param _velocity New value for member velocity + */ +void CarlaEgoVehicleStatus::velocity( + float _velocity) +{ + m_velocity = _velocity; +} + +/*! + * @brief This function returns the value of member velocity + * @return Value of member velocity + */ +float CarlaEgoVehicleStatus::velocity() const +{ + return m_velocity; +} + +/*! + * @brief This function returns a reference to member velocity + * @return Reference to member velocity + */ +float& CarlaEgoVehicleStatus::velocity() +{ + return m_velocity; +} + + +/*! + * @brief This function copies the value in member acceleration + * @param _acceleration New value to be copied in member acceleration + */ +void CarlaEgoVehicleStatus::acceleration( + const geometry_msgs::msg::Accel& _acceleration) +{ + m_acceleration = _acceleration; +} + +/*! + * @brief This function moves the value in member acceleration + * @param _acceleration New value to be moved in member acceleration + */ +void CarlaEgoVehicleStatus::acceleration( + geometry_msgs::msg::Accel&& _acceleration) +{ + m_acceleration = std::move(_acceleration); +} + +/*! + * @brief This function returns a constant reference to member acceleration + * @return Constant reference to member acceleration + */ +const geometry_msgs::msg::Accel& CarlaEgoVehicleStatus::acceleration() const +{ + return m_acceleration; +} + +/*! + * @brief This function returns a reference to member acceleration + * @return Reference to member acceleration + */ +geometry_msgs::msg::Accel& CarlaEgoVehicleStatus::acceleration() +{ + return m_acceleration; +} + + +/*! + * @brief This function copies the value in member orientation + * @param _orientation New value to be copied in member orientation + */ +void CarlaEgoVehicleStatus::orientation( + const geometry_msgs::msg::Quaternion& _orientation) +{ + m_orientation = _orientation; +} + +/*! + * @brief This function moves the value in member orientation + * @param _orientation New value to be moved in member orientation + */ +void CarlaEgoVehicleStatus::orientation( + geometry_msgs::msg::Quaternion&& _orientation) +{ + m_orientation = std::move(_orientation); +} + +/*! + * @brief This function returns a constant reference to member orientation + * @return Constant reference to member orientation + */ +const geometry_msgs::msg::Quaternion& CarlaEgoVehicleStatus::orientation() const +{ + return m_orientation; +} + +/*! + * @brief This function returns a reference to member orientation + * @return Reference to member orientation + */ +geometry_msgs::msg::Quaternion& CarlaEgoVehicleStatus::orientation() +{ + return m_orientation; +} + + +/*! + * @brief This function sets a value in member active_control_type + * @param _active_control_type New value for member active_control_type + */ +void CarlaEgoVehicleStatus::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 CarlaEgoVehicleStatus::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& CarlaEgoVehicleStatus::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 CarlaEgoVehicleStatus::last_applied_vehicle_control( + const carla_msgs::msg::CarlaEgoVehicleControl& _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 CarlaEgoVehicleStatus::last_applied_vehicle_control( + carla_msgs::msg::CarlaEgoVehicleControl&& _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::CarlaEgoVehicleControl& CarlaEgoVehicleStatus::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::CarlaEgoVehicleControl& CarlaEgoVehicleStatus::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 CarlaEgoVehicleStatus::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 CarlaEgoVehicleStatus::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& CarlaEgoVehicleStatus::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& CarlaEgoVehicleStatus::last_applied_ackermann_control() +{ + return m_last_applied_ackermann_control; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaEgoVehicleStatusCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatus.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatus.h new file mode 100644 index 00000000000..44d4da4a2bf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatus.h @@ -0,0 +1,340 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleStatus.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUS_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "geometry_msgs/msg/Quaternion.h" +#include "CarlaEgoVehicleControl.h" +#include "geometry_msgs/msg/Accel.h" +#include "ackermann_msgs/msg/AckermannDriveStamped.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(CARLAEGOVEHICLESTATUS_SOURCE) +#define CARLAEGOVEHICLESTATUS_DllAPI __declspec( dllexport ) +#else +#define CARLAEGOVEHICLESTATUS_DllAPI __declspec( dllimport ) +#endif // CARLAEGOVEHICLESTATUS_SOURCE +#else +#define CARLAEGOVEHICLESTATUS_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLAEGOVEHICLESTATUS_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + +namespace CarlaEgoVehicleStatus_Constants { + +const uint8_t VEHICLE_CONTROL = 0; +const uint8_t ACKERMANN_CONTROL = 1; + +} // namespace CarlaEgoVehicleStatus_Constants + + +/*! + * @brief This class represents the structure CarlaEgoVehicleStatus defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleStatus + */ +class CarlaEgoVehicleStatus +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaEgoVehicleStatus(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaEgoVehicleStatus(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleStatus that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleStatus( + const CarlaEgoVehicleStatus& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleStatus that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleStatus( + CarlaEgoVehicleStatus&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleStatus that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleStatus& operator =( + const CarlaEgoVehicleStatus& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleStatus that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleStatus& operator =( + CarlaEgoVehicleStatus&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleStatus object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaEgoVehicleStatus& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleStatus object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaEgoVehicleStatus& 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 velocity + * @param _velocity New value for member velocity + */ + eProsima_user_DllExport void velocity( + float _velocity); + + /*! + * @brief This function returns the value of member velocity + * @return Value of member velocity + */ + eProsima_user_DllExport float velocity() const; + + /*! + * @brief This function returns a reference to member velocity + * @return Reference to member velocity + */ + eProsima_user_DllExport float& velocity(); + + + /*! + * @brief This function copies the value in member acceleration + * @param _acceleration New value to be copied in member acceleration + */ + eProsima_user_DllExport void acceleration( + const geometry_msgs::msg::Accel& _acceleration); + + /*! + * @brief This function moves the value in member acceleration + * @param _acceleration New value to be moved in member acceleration + */ + eProsima_user_DllExport void acceleration( + geometry_msgs::msg::Accel&& _acceleration); + + /*! + * @brief This function returns a constant reference to member acceleration + * @return Constant reference to member acceleration + */ + eProsima_user_DllExport const geometry_msgs::msg::Accel& acceleration() const; + + /*! + * @brief This function returns a reference to member acceleration + * @return Reference to member acceleration + */ + eProsima_user_DllExport geometry_msgs::msg::Accel& acceleration(); + + + /*! + * @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 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::CarlaEgoVehicleControl& _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::CarlaEgoVehicleControl&& _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::CarlaEgoVehicleControl& 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::CarlaEgoVehicleControl& 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(); + +private: + + std_msgs::msg::Header m_header; + float m_velocity{0.0}; + geometry_msgs::msg::Accel m_acceleration; + geometry_msgs::msg::Quaternion m_orientation; + uint8_t m_active_control_type{0}; + carla_msgs::msg::CarlaEgoVehicleControl 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_CARLAEGOVEHICLESTATUS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusCdrAux.hpp new file mode 100644 index 00000000000..1f5af9f648e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusCdrAux.hpp @@ -0,0 +1,60 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleStatusCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUSCDRAUX_HPP_ + +#include "CarlaEgoVehicleStatus.h" + +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleStatus_max_cdr_typesize {1004UL}; +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleStatus_max_key_cdr_typesize {0UL}; + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleStatus& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusCdrAux.ipp new file mode 100644 index 00000000000..1eb5497de48 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusCdrAux.ipp @@ -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 CarlaEgoVehicleStatusCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUSCDRAUX_IPP_ + +#include "CarlaEgoVehicleStatusCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaEgoVehicleStatus& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.velocity(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.acceleration(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.orientation(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.active_control_type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.last_applied_vehicle_control(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.last_applied_ackermann_control(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleStatus& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.velocity() + << eprosima::fastcdr::MemberId(2) << data.acceleration() + << eprosima::fastcdr::MemberId(3) << data.orientation() + << eprosima::fastcdr::MemberId(4) << data.active_control_type() + << eprosima::fastcdr::MemberId(5) << data.last_applied_vehicle_control() + << eprosima::fastcdr::MemberId(6) << data.last_applied_ackermann_control() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaEgoVehicleStatus& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.velocity(); + break; + + case 2: + dcdr >> data.acceleration(); + break; + + case 3: + dcdr >> data.orientation(); + break; + + case 4: + dcdr >> data.active_control_type(); + break; + + case 5: + dcdr >> data.last_applied_vehicle_control(); + break; + + case 6: + dcdr >> data.last_applied_ackermann_control(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleStatus& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUSCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusPubSubTypes.cxx new file mode 100644 index 00000000000..7d67c4ba678 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusPubSubTypes.cxx @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleStatusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaEgoVehicleStatusPubSubTypes.h" +#include "CarlaEgoVehicleStatusCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { +namespace CarlaEgoVehicleStatus_Constants { + + + + + +} //End of namespace CarlaEgoVehicleStatus_Constants + + + +CarlaEgoVehicleStatusPubSubType::CarlaEgoVehicleStatusPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaEgoVehicleStatus_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaEgoVehicleStatus::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaEgoVehicleStatus_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaEgoVehicleStatusPubSubType::~CarlaEgoVehicleStatusPubSubType() +{ +} + +bool CarlaEgoVehicleStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CarlaEgoVehicleStatus* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaEgoVehicleStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + CarlaEgoVehicleStatus* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaEgoVehicleStatusPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CarlaEgoVehicleStatusPubSubType::createData() +{ + return reinterpret_cast(new CarlaEgoVehicleStatus()); +} + +void CarlaEgoVehicleStatusPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CarlaEgoVehicleStatusPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusPubSubTypes.h new file mode 100644 index 00000000000..4626127cf64 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleStatusPubSubTypes.h @@ -0,0 +1,145 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleStatusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUS_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaEgoVehicleStatus.h" + +#include "geometry_msgs/msg/QuaternionPubSubTypes.h" +#include "CarlaEgoVehicleControlPubSubTypes.h" +#include "geometry_msgs/msg/AccelPubSubTypes.h" +#include "ackermann_msgs/msg/AckermannDriveStampedPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaEgoVehicleStatus is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs { +namespace msg { +namespace CarlaEgoVehicleStatus_Constants { + + + + +} // namespace CarlaEgoVehicleStatus_Constants + + + +/*! + * @brief This class represents the TopicDataType of the type CarlaEgoVehicleStatus defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleStatus + */ +class CarlaEgoVehicleStatusPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaEgoVehicleStatus type; + + eProsima_user_DllExport CarlaEgoVehicleStatusPubSubType(); + + eProsima_user_DllExport ~CarlaEgoVehicleStatusPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLESTATUS_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryData.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryData.cxx new file mode 100644 index 00000000000..b6ac46ca57f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryData.cxx @@ -0,0 +1,461 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleTelemetryData.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaEgoVehicleTelemetryData.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace carla_msgs { + +namespace msg { + +namespace CarlaEgoVehicleTelemetryData_Constants { + + +} // namespace CarlaEgoVehicleTelemetryData_Constants + + +CarlaEgoVehicleTelemetryData::CarlaEgoVehicleTelemetryData() +{ +} + +CarlaEgoVehicleTelemetryData::~CarlaEgoVehicleTelemetryData() +{ +} + +CarlaEgoVehicleTelemetryData::CarlaEgoVehicleTelemetryData( + const CarlaEgoVehicleTelemetryData& 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; + m_light_state_flags = x.m_light_state_flags; +} + +CarlaEgoVehicleTelemetryData::CarlaEgoVehicleTelemetryData( + CarlaEgoVehicleTelemetryData&& x) noexcept +{ + 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); + m_light_state_flags = x.m_light_state_flags; +} + +CarlaEgoVehicleTelemetryData& CarlaEgoVehicleTelemetryData::operator =( + const CarlaEgoVehicleTelemetryData& 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; + m_light_state_flags = x.m_light_state_flags; + return *this; +} + +CarlaEgoVehicleTelemetryData& CarlaEgoVehicleTelemetryData::operator =( + CarlaEgoVehicleTelemetryData&& x) noexcept +{ + + 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); + m_light_state_flags = x.m_light_state_flags; + return *this; +} + +bool CarlaEgoVehicleTelemetryData::operator ==( + const CarlaEgoVehicleTelemetryData& 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 && + m_light_state_flags == x.m_light_state_flags); +} + +bool CarlaEgoVehicleTelemetryData::operator !=( + const CarlaEgoVehicleTelemetryData& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void CarlaEgoVehicleTelemetryData::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 CarlaEgoVehicleTelemetryData::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& CarlaEgoVehicleTelemetryData::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& CarlaEgoVehicleTelemetryData::header() +{ + return m_header; +} + + +/*! + * @brief This function sets a value in member speed + * @param _speed New value for member speed + */ +void CarlaEgoVehicleTelemetryData::speed( + float _speed) +{ + m_speed = _speed; +} + +/*! + * @brief This function returns the value of member speed + * @return Value of member speed + */ +float CarlaEgoVehicleTelemetryData::speed() const +{ + return m_speed; +} + +/*! + * @brief This function returns a reference to member speed + * @return Reference to member speed + */ +float& CarlaEgoVehicleTelemetryData::speed() +{ + return m_speed; +} + + +/*! + * @brief This function sets a value in member steer + * @param _steer New value for member steer + */ +void CarlaEgoVehicleTelemetryData::steer( + float _steer) +{ + m_steer = _steer; +} + +/*! + * @brief This function returns the value of member steer + * @return Value of member steer + */ +float CarlaEgoVehicleTelemetryData::steer() const +{ + return m_steer; +} + +/*! + * @brief This function returns a reference to member steer + * @return Reference to member steer + */ +float& CarlaEgoVehicleTelemetryData::steer() +{ + return m_steer; +} + + +/*! + * @brief This function sets a value in member throttle + * @param _throttle New value for member throttle + */ +void CarlaEgoVehicleTelemetryData::throttle( + float _throttle) +{ + m_throttle = _throttle; +} + +/*! + * @brief This function returns the value of member throttle + * @return Value of member throttle + */ +float CarlaEgoVehicleTelemetryData::throttle() const +{ + return m_throttle; +} + +/*! + * @brief This function returns a reference to member throttle + * @return Reference to member throttle + */ +float& CarlaEgoVehicleTelemetryData::throttle() +{ + return m_throttle; +} + + +/*! + * @brief This function sets a value in member brake + * @param _brake New value for member brake + */ +void CarlaEgoVehicleTelemetryData::brake( + float _brake) +{ + m_brake = _brake; +} + +/*! + * @brief This function returns the value of member brake + * @return Value of member brake + */ +float CarlaEgoVehicleTelemetryData::brake() const +{ + return m_brake; +} + +/*! + * @brief This function returns a reference to member brake + * @return Reference to member brake + */ +float& CarlaEgoVehicleTelemetryData::brake() +{ + return m_brake; +} + + +/*! + * @brief This function sets a value in member engine_rpm + * @param _engine_rpm New value for member engine_rpm + */ +void CarlaEgoVehicleTelemetryData::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 CarlaEgoVehicleTelemetryData::engine_rpm() const +{ + return m_engine_rpm; +} + +/*! + * @brief This function returns a reference to member engine_rpm + * @return Reference to member engine_rpm + */ +float& CarlaEgoVehicleTelemetryData::engine_rpm() +{ + return m_engine_rpm; +} + + +/*! + * @brief This function sets a value in member gear + * @param _gear New value for member gear + */ +void CarlaEgoVehicleTelemetryData::gear( + int32_t _gear) +{ + m_gear = _gear; +} + +/*! + * @brief This function returns the value of member gear + * @return Value of member gear + */ +int32_t CarlaEgoVehicleTelemetryData::gear() const +{ + return m_gear; +} + +/*! + * @brief This function returns a reference to member gear + * @return Reference to member gear + */ +int32_t& CarlaEgoVehicleTelemetryData::gear() +{ + return m_gear; +} + + +/*! + * @brief This function sets a value in member drag + * @param _drag New value for member drag + */ +void CarlaEgoVehicleTelemetryData::drag( + float _drag) +{ + m_drag = _drag; +} + +/*! + * @brief This function returns the value of member drag + * @return Value of member drag + */ +float CarlaEgoVehicleTelemetryData::drag() const +{ + return m_drag; +} + +/*! + * @brief This function returns a reference to member drag + * @return Reference to member drag + */ +float& CarlaEgoVehicleTelemetryData::drag() +{ + return m_drag; +} + + +/*! + * @brief This function copies the value in member wheels + * @param _wheels New value to be copied in member wheels + */ +void CarlaEgoVehicleTelemetryData::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 CarlaEgoVehicleTelemetryData::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& CarlaEgoVehicleTelemetryData::wheels() const +{ + return m_wheels; +} + +/*! + * @brief This function returns a reference to member wheels + * @return Reference to member wheels + */ +std::vector& CarlaEgoVehicleTelemetryData::wheels() +{ + return m_wheels; +} + + +/*! + * @brief This function sets a value in member light_state_flags + * @param _light_state_flags New value for member light_state_flags + */ +void CarlaEgoVehicleTelemetryData::light_state_flags( + uint32_t _light_state_flags) +{ + m_light_state_flags = _light_state_flags; +} + +/*! + * @brief This function returns the value of member light_state_flags + * @return Value of member light_state_flags + */ +uint32_t CarlaEgoVehicleTelemetryData::light_state_flags() const +{ + return m_light_state_flags; +} + +/*! + * @brief This function returns a reference to member light_state_flags + * @return Reference to member light_state_flags + */ +uint32_t& CarlaEgoVehicleTelemetryData::light_state_flags() +{ + return m_light_state_flags; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaEgoVehicleTelemetryDataCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryData.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryData.h new file mode 100644 index 00000000000..c46da700ef8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryData.h @@ -0,0 +1,391 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleTelemetryData.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATA_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATA_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CarlaEgoVehicleTelemetryDataWheel.h" +#include "std_msgs/msg/Header.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(CARLAEGOVEHICLETELEMETRYDATA_SOURCE) +#define CARLAEGOVEHICLETELEMETRYDATA_DllAPI __declspec( dllexport ) +#else +#define CARLAEGOVEHICLETELEMETRYDATA_DllAPI __declspec( dllimport ) +#endif // CARLAEGOVEHICLETELEMETRYDATA_SOURCE +#else +#define CARLAEGOVEHICLETELEMETRYDATA_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLAEGOVEHICLETELEMETRYDATA_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + +namespace CarlaEgoVehicleTelemetryData_Constants { + +const uint32_t LIGHTSTATEFLAG_NONE = 0; +const uint32_t LIGHTSTATEFLAG_POSITION = 1; +const uint32_t LIGHTSTATEFLAG_LOWBEAM = 2; +const uint32_t LIGHTSTATEFLAG_HIGHBEAM = 4; +const uint32_t LIGHTSTATEFLAG_BRAKE = 8; +const uint32_t LIGHTSTATEFLAG_RIGHTBLINKER = 16; +const uint32_t LIGHTSTATEFLAG_LEFTBLINKER = 32; +const uint32_t LIGHTSTATEFLAG_REVERSE = 64; +const uint32_t LIGHTSTATEFLAG_FOG = 128; +const uint32_t LIGHTSTATEFLAG_INTERIOR = 256; +const uint32_t LIGHTSTATEFLAG_SPECIAL1 = 512; +const uint32_t LIGHTSTATEFLAG_SPECIAL2 = 1024; +const uint32_t LIGHTSTATEFLAG_ALL = 4294967295; + +} // namespace CarlaEgoVehicleTelemetryData_Constants + + +/*! + * @brief This class represents the structure CarlaEgoVehicleTelemetryData defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleTelemetryData + */ +class CarlaEgoVehicleTelemetryData +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaEgoVehicleTelemetryData(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaEgoVehicleTelemetryData(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleTelemetryData that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleTelemetryData( + const CarlaEgoVehicleTelemetryData& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleTelemetryData that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleTelemetryData( + CarlaEgoVehicleTelemetryData&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleTelemetryData that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleTelemetryData& operator =( + const CarlaEgoVehicleTelemetryData& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleTelemetryData that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleTelemetryData& operator =( + CarlaEgoVehicleTelemetryData&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleTelemetryData object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaEgoVehicleTelemetryData& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleTelemetryData object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaEgoVehicleTelemetryData& 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 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 steer + * @param _steer New value for member steer + */ + eProsima_user_DllExport void steer( + float _steer); + + /*! + * @brief This function returns the value of member steer + * @return Value of member steer + */ + eProsima_user_DllExport float steer() const; + + /*! + * @brief This function returns a reference to member steer + * @return Reference to member steer + */ + eProsima_user_DllExport float& steer(); + + + /*! + * @brief This function sets a value in member throttle + * @param _throttle New value for member throttle + */ + eProsima_user_DllExport void throttle( + float _throttle); + + /*! + * @brief This function returns the value of member throttle + * @return Value of member throttle + */ + eProsima_user_DllExport float throttle() const; + + /*! + * @brief This function returns a reference to member throttle + * @return Reference to member throttle + */ + eProsima_user_DllExport float& throttle(); + + + /*! + * @brief This function sets a value in member brake + * @param _brake New value for member brake + */ + eProsima_user_DllExport void brake( + float _brake); + + /*! + * @brief This function returns the value of member brake + * @return Value of member brake + */ + eProsima_user_DllExport float brake() const; + + /*! + * @brief This function returns a reference to member brake + * @return Reference to member brake + */ + eProsima_user_DllExport float& brake(); + + + /*! + * @brief This function sets a value in member engine_rpm + * @param _engine_rpm New value for member engine_rpm + */ + eProsima_user_DllExport void engine_rpm( + float _engine_rpm); + + /*! + * @brief This function returns the value of member engine_rpm + * @return Value of member engine_rpm + */ + eProsima_user_DllExport float engine_rpm() const; + + /*! + * @brief This function returns a reference to member engine_rpm + * @return Reference to member engine_rpm + */ + eProsima_user_DllExport float& engine_rpm(); + + + /*! + * @brief This function sets a value in member gear + * @param _gear New value for member gear + */ + eProsima_user_DllExport void gear( + int32_t _gear); + + /*! + * @brief This function returns the value of member gear + * @return Value of member gear + */ + eProsima_user_DllExport int32_t gear() const; + + /*! + * @brief This function returns a reference to member gear + * @return Reference to member gear + */ + eProsima_user_DllExport int32_t& gear(); + + + /*! + * @brief This function sets a value in member drag + * @param _drag New value for member drag + */ + eProsima_user_DllExport void drag( + float _drag); + + /*! + * @brief This function returns the value of member drag + * @return Value of member drag + */ + eProsima_user_DllExport float drag() const; + + /*! + * @brief This function returns a reference to member drag + * @return Reference to member drag + */ + eProsima_user_DllExport float& drag(); + + + /*! + * @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 light_state_flags + * @param _light_state_flags New value for member light_state_flags + */ + eProsima_user_DllExport void light_state_flags( + uint32_t _light_state_flags); + + /*! + * @brief This function returns the value of member light_state_flags + * @return Value of member light_state_flags + */ + eProsima_user_DllExport uint32_t light_state_flags() const; + + /*! + * @brief This function returns a reference to member light_state_flags + * @return Reference to member light_state_flags + */ + eProsima_user_DllExport uint32_t& light_state_flags(); + +private: + + std_msgs::msg::Header m_header; + float m_speed{0.0}; + float m_steer{0.0}; + float m_throttle{0.0}; + float m_brake{0.0}; + float m_engine_rpm{0.0}; + int32_t m_gear{0}; + float m_drag{0.0}; + std::vector m_wheels; + uint32_t m_light_state_flags{0}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATA_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataCdrAux.hpp new file mode 100644 index 00000000000..19f339d0200 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataCdrAux.hpp @@ -0,0 +1,78 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleTelemetryDataCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATACDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATACDRAUX_HPP_ + +#include "CarlaEgoVehicleTelemetryData.h" + +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleTelemetryData_max_cdr_typesize {5120UL}; +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleTelemetryData_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleTelemetryData& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATACDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataCdrAux.ipp new file mode 100644 index 00000000000..793222c19ba --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataCdrAux.ipp @@ -0,0 +1,229 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleTelemetryDataCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATACDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATACDRAUX_IPP_ + +#include "CarlaEgoVehicleTelemetryDataCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaEgoVehicleTelemetryData& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.speed(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.steer(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.throttle(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.brake(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.engine_rpm(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.gear(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.drag(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.wheels(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), + data.light_state_flags(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleTelemetryData& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.speed() + << eprosima::fastcdr::MemberId(2) << data.steer() + << eprosima::fastcdr::MemberId(3) << data.throttle() + << eprosima::fastcdr::MemberId(4) << data.brake() + << eprosima::fastcdr::MemberId(5) << data.engine_rpm() + << eprosima::fastcdr::MemberId(6) << data.gear() + << eprosima::fastcdr::MemberId(7) << data.drag() + << eprosima::fastcdr::MemberId(8) << data.wheels() + << eprosima::fastcdr::MemberId(9) << data.light_state_flags() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaEgoVehicleTelemetryData& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.speed(); + break; + + case 2: + dcdr >> data.steer(); + break; + + case 3: + dcdr >> data.throttle(); + break; + + case 4: + dcdr >> data.brake(); + break; + + case 5: + dcdr >> data.engine_rpm(); + break; + + case 6: + dcdr >> data.gear(); + break; + + case 7: + dcdr >> data.drag(); + break; + + case 8: + dcdr >> data.wheels(); + break; + + case 9: + dcdr >> data.light_state_flags(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleTelemetryData& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATACDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataPubSubTypes.cxx new file mode 100644 index 00000000000..e712b26ae9d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataPubSubTypes.cxx @@ -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 CarlaEgoVehicleTelemetryDataPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaEgoVehicleTelemetryDataPubSubTypes.h" +#include "CarlaEgoVehicleTelemetryDataCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { +namespace CarlaEgoVehicleTelemetryData_Constants { + + + + + + + + + + + + + + + + + + + + + + + + + + + +} //End of namespace CarlaEgoVehicleTelemetryData_Constants + + + +CarlaEgoVehicleTelemetryDataPubSubType::CarlaEgoVehicleTelemetryDataPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaEgoVehicleTelemetryData_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaEgoVehicleTelemetryData::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaEgoVehicleTelemetryData_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaEgoVehicleTelemetryDataPubSubType::~CarlaEgoVehicleTelemetryDataPubSubType() +{ +} + +bool CarlaEgoVehicleTelemetryDataPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CarlaEgoVehicleTelemetryData* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaEgoVehicleTelemetryDataPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + CarlaEgoVehicleTelemetryData* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaEgoVehicleTelemetryDataPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CarlaEgoVehicleTelemetryDataPubSubType::createData() +{ + return reinterpret_cast(new CarlaEgoVehicleTelemetryData()); +} + +void CarlaEgoVehicleTelemetryDataPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CarlaEgoVehicleTelemetryDataPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataPubSubTypes.h new file mode 100644 index 00000000000..d5ba58c0285 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataPubSubTypes.h @@ -0,0 +1,165 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleTelemetryDataPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATA_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATA_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaEgoVehicleTelemetryData.h" + +#include "CarlaEgoVehicleTelemetryDataWheelPubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaEgoVehicleTelemetryData is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace carla_msgs { +namespace msg { +namespace CarlaEgoVehicleTelemetryData_Constants { + + + + + + + + + + + + + + + + + + + + + + + + + + +} // namespace CarlaEgoVehicleTelemetryData_Constants + + + +/*! + * @brief This class represents the TopicDataType of the type CarlaEgoVehicleTelemetryData defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleTelemetryData + */ +class CarlaEgoVehicleTelemetryDataPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaEgoVehicleTelemetryData type; + + eProsima_user_DllExport CarlaEgoVehicleTelemetryDataPubSubType(); + + eProsima_user_DllExport ~CarlaEgoVehicleTelemetryDataPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATA_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheel.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheel.cxx new file mode 100644 index 00000000000..4efe63b7837 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheel.cxx @@ -0,0 +1,471 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleTelemetryDataWheel.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CarlaEgoVehicleTelemetryDataWheel.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace carla_msgs { + +namespace msg { + + + +CarlaEgoVehicleTelemetryDataWheel::CarlaEgoVehicleTelemetryDataWheel() +{ +} + +CarlaEgoVehicleTelemetryDataWheel::~CarlaEgoVehicleTelemetryDataWheel() +{ +} + +CarlaEgoVehicleTelemetryDataWheel::CarlaEgoVehicleTelemetryDataWheel( + const CarlaEgoVehicleTelemetryDataWheel& 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; +} + +CarlaEgoVehicleTelemetryDataWheel::CarlaEgoVehicleTelemetryDataWheel( + CarlaEgoVehicleTelemetryDataWheel&& x) noexcept +{ + 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; +} + +CarlaEgoVehicleTelemetryDataWheel& CarlaEgoVehicleTelemetryDataWheel::operator =( + const CarlaEgoVehicleTelemetryDataWheel& 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; +} + +CarlaEgoVehicleTelemetryDataWheel& CarlaEgoVehicleTelemetryDataWheel::operator =( + CarlaEgoVehicleTelemetryDataWheel&& x) noexcept +{ + + 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 CarlaEgoVehicleTelemetryDataWheel::operator ==( + const CarlaEgoVehicleTelemetryDataWheel& 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 CarlaEgoVehicleTelemetryDataWheel::operator !=( + const CarlaEgoVehicleTelemetryDataWheel& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member tire_friction + * @param _tire_friction New value for member tire_friction + */ +void CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::tire_friction() const +{ + return m_tire_friction; +} + +/*! + * @brief This function returns a reference to member tire_friction + * @return Reference to member tire_friction + */ +float& CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::lat_slip() const +{ + return m_lat_slip; +} + +/*! + * @brief This function returns a reference to member lat_slip + * @return Reference to member lat_slip + */ +float& CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::long_slip() const +{ + return m_long_slip; +} + +/*! + * @brief This function returns a reference to member long_slip + * @return Reference to member long_slip + */ +float& CarlaEgoVehicleTelemetryDataWheel::long_slip() +{ + return m_long_slip; +} + + +/*! + * @brief This function sets a value in member omega + * @param _omega New value for member omega + */ +void CarlaEgoVehicleTelemetryDataWheel::omega( + float _omega) +{ + m_omega = _omega; +} + +/*! + * @brief This function returns the value of member omega + * @return Value of member omega + */ +float CarlaEgoVehicleTelemetryDataWheel::omega() const +{ + return m_omega; +} + +/*! + * @brief This function returns a reference to member omega + * @return Reference to member omega + */ +float& CarlaEgoVehicleTelemetryDataWheel::omega() +{ + return m_omega; +} + + +/*! + * @brief This function sets a value in member tire_load + * @param _tire_load New value for member tire_load + */ +void CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::tire_load() const +{ + return m_tire_load; +} + +/*! + * @brief This function returns a reference to member tire_load + * @return Reference to member tire_load + */ +float& CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::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& CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::torque( + float _torque) +{ + m_torque = _torque; +} + +/*! + * @brief This function returns the value of member torque + * @return Value of member torque + */ +float CarlaEgoVehicleTelemetryDataWheel::torque() const +{ + return m_torque; +} + +/*! + * @brief This function returns a reference to member torque + * @return Reference to member torque + */ +float& CarlaEgoVehicleTelemetryDataWheel::torque() +{ + return m_torque; +} + + +/*! + * @brief This function sets a value in member long_force + * @param _long_force New value for member long_force + */ +void CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::long_force() const +{ + return m_long_force; +} + +/*! + * @brief This function returns a reference to member long_force + * @return Reference to member long_force + */ +float& CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::lat_force() const +{ + return m_lat_force; +} + +/*! + * @brief This function returns a reference to member lat_force + * @return Reference to member lat_force + */ +float& CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::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& CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::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 CarlaEgoVehicleTelemetryDataWheel::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& CarlaEgoVehicleTelemetryDataWheel::normalized_lat_force() +{ + return m_normalized_lat_force; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaEgoVehicleTelemetryDataWheelCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheel.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheel.h new file mode 100644 index 00000000000..d4d84aab5d2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheel.h @@ -0,0 +1,379 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleTelemetryDataWheel.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEEL_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEEL_H_ + +#include +#include +#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(CARLAEGOVEHICLETELEMETRYDATAWHEEL_SOURCE) +#define CARLAEGOVEHICLETELEMETRYDATAWHEEL_DllAPI __declspec( dllexport ) +#else +#define CARLAEGOVEHICLETELEMETRYDATAWHEEL_DllAPI __declspec( dllimport ) +#endif // CARLAEGOVEHICLETELEMETRYDATAWHEEL_SOURCE +#else +#define CARLAEGOVEHICLETELEMETRYDATAWHEEL_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLAEGOVEHICLETELEMETRYDATAWHEEL_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure CarlaEgoVehicleTelemetryDataWheel defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleTelemetryDataWheel + */ +class CarlaEgoVehicleTelemetryDataWheel +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaEgoVehicleTelemetryDataWheel(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaEgoVehicleTelemetryDataWheel(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleTelemetryDataWheel( + const CarlaEgoVehicleTelemetryDataWheel& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleTelemetryDataWheel( + CarlaEgoVehicleTelemetryDataWheel&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleTelemetryDataWheel& operator =( + const CarlaEgoVehicleTelemetryDataWheel& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel that will be copied. + */ + eProsima_user_DllExport CarlaEgoVehicleTelemetryDataWheel& operator =( + CarlaEgoVehicleTelemetryDataWheel&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaEgoVehicleTelemetryDataWheel& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaEgoVehicleTelemetryDataWheel& 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(); + +private: + + float m_tire_friction{0.0}; + float m_lat_slip{0.0}; + float m_long_slip{0.0}; + float m_omega{0.0}; + float m_tire_load{0.0}; + float m_normalized_tire_load{0.0}; + float m_torque{0.0}; + float m_long_force{0.0}; + float m_lat_force{0.0}; + float m_normalized_long_force{0.0}; + float m_normalized_lat_force{0.0}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEEL_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelCdrAux.hpp new file mode 100644 index 00000000000..2ebe1b65a89 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEgoVehicleTelemetryDataWheelCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEELCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEELCDRAUX_HPP_ + +#include "CarlaEgoVehicleTelemetryDataWheel.h" + +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleTelemetryDataWheel_max_cdr_typesize {48UL}; +constexpr uint32_t carla_msgs_msg_CarlaEgoVehicleTelemetryDataWheel_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEELCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelCdrAux.ipp new file mode 100644 index 00000000000..5a5f864c253 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelCdrAux.ipp @@ -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 CarlaEgoVehicleTelemetryDataWheelCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEELCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEELCDRAUX_IPP_ + +#include "CarlaEgoVehicleTelemetryDataWheelCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.tire_friction(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.lat_slip(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.long_slip(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.omega(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.tire_load(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.normalized_tire_load(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.torque(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.long_force(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.lat_force(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), + data.normalized_long_force(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(10), + data.normalized_lat_force(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.tire_friction() + << eprosima::fastcdr::MemberId(1) << data.lat_slip() + << eprosima::fastcdr::MemberId(2) << data.long_slip() + << eprosima::fastcdr::MemberId(3) << data.omega() + << eprosima::fastcdr::MemberId(4) << data.tire_load() + << eprosima::fastcdr::MemberId(5) << data.normalized_tire_load() + << eprosima::fastcdr::MemberId(6) << data.torque() + << eprosima::fastcdr::MemberId(7) << data.long_force() + << eprosima::fastcdr::MemberId(8) << data.lat_force() + << eprosima::fastcdr::MemberId(9) << data.normalized_long_force() + << eprosima::fastcdr::MemberId(10) << data.normalized_lat_force() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.tire_friction(); + break; + + case 1: + dcdr >> data.lat_slip(); + break; + + case 2: + dcdr >> data.long_slip(); + break; + + case 3: + dcdr >> data.omega(); + break; + + case 4: + dcdr >> data.tire_load(); + break; + + case 5: + dcdr >> data.normalized_tire_load(); + break; + + case 6: + dcdr >> data.torque(); + break; + + case 7: + dcdr >> data.long_force(); + break; + + case 8: + dcdr >> data.lat_force(); + break; + + case 9: + dcdr >> data.normalized_long_force(); + break; + + case 10: + dcdr >> data.normalized_lat_force(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEgoVehicleTelemetryDataWheel& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEELCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelPubSubTypes.cxx new file mode 100644 index 00000000000..29d4de28ff7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelPubSubTypes.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 CarlaEgoVehicleTelemetryDataWheelPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaEgoVehicleTelemetryDataWheelPubSubTypes.h" +#include "CarlaEgoVehicleTelemetryDataWheelCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaEgoVehicleTelemetryDataWheelPubSubType::CarlaEgoVehicleTelemetryDataWheelPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaEgoVehicleTelemetryDataWheel_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaEgoVehicleTelemetryDataWheel::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaEgoVehicleTelemetryDataWheel_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaEgoVehicleTelemetryDataWheelPubSubType::~CarlaEgoVehicleTelemetryDataWheelPubSubType() +{ +} + +bool CarlaEgoVehicleTelemetryDataWheelPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CarlaEgoVehicleTelemetryDataWheel* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaEgoVehicleTelemetryDataWheelPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + CarlaEgoVehicleTelemetryDataWheel* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaEgoVehicleTelemetryDataWheelPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CarlaEgoVehicleTelemetryDataWheelPubSubType::createData() +{ + return reinterpret_cast(new CarlaEgoVehicleTelemetryDataWheel()); +} + +void CarlaEgoVehicleTelemetryDataWheelPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CarlaEgoVehicleTelemetryDataWheelPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelPubSubTypes.h new file mode 100644 index 00000000000..13e21844cda --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEgoVehicleTelemetryDataWheelPubSubTypes.h @@ -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 CarlaEgoVehicleTelemetryDataWheelPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEEL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEEL_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaEgoVehicleTelemetryDataWheel.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaEgoVehicleTelemetryDataWheel 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 CarlaEgoVehicleTelemetryDataWheel defined by the user in the IDL file. + * @ingroup CarlaEgoVehicleTelemetryDataWheel + */ +class CarlaEgoVehicleTelemetryDataWheelPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaEgoVehicleTelemetryDataWheel type; + + eProsima_user_DllExport CarlaEgoVehicleTelemetryDataWheelPubSubType(); + + eProsima_user_DllExport ~CarlaEgoVehicleTelemetryDataWheelPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOVEHICLETELEMETRYDATAWHEEL_PUBSUBTYPES_H_ + 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..79f65df9c2b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettings.cxx @@ -0,0 +1,471 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaEpisodeSettings::CarlaEpisodeSettings() +{ +} + +CarlaEpisodeSettings::~CarlaEpisodeSettings() +{ +} + +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; +} + +CarlaEpisodeSettings::CarlaEpisodeSettings( + CarlaEpisodeSettings&& x) noexcept +{ + 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; +} + +CarlaEpisodeSettings& 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; +} + +CarlaEpisodeSettings& CarlaEpisodeSettings::operator =( + CarlaEpisodeSettings&& x) noexcept +{ + + 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 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 CarlaEpisodeSettings::operator !=( + const CarlaEpisodeSettings& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member synchronous_mode + * @param _synchronous_mode New value for member synchronous_mode + */ +void 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 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& 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 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 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& 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 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 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& 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 CarlaEpisodeSettings::substepping( + bool _substepping) +{ + m_substepping = _substepping; +} + +/*! + * @brief This function returns the value of member substepping + * @return Value of member substepping + */ +bool CarlaEpisodeSettings::substepping() const +{ + return m_substepping; +} + +/*! + * @brief This function returns a reference to member substepping + * @return Reference to member substepping + */ +bool& 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 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 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& 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 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 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& 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 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 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& 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 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 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& 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 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 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& 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 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 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& 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 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 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& CarlaEpisodeSettings::spectator_as_ego() +{ + return m_spectator_as_ego; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaEpisodeSettingsCdrAux.ipp" + 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..b33077b5b7b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettings.h @@ -0,0 +1,379 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_H_ + +#include +#include +#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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + bool m_synchronous_mode{false}; + bool m_no_rendering_mode{false}; + double m_fixed_delta_seconds{0.0}; + bool m_substepping{true}; + double m_max_substep_delta_time{0.01}; + int32_t m_max_substeps{10}; + float m_max_culling_distance{0.0}; + bool m_deterministic_ragdolls{false}; + float m_tile_stream_distance{3000.0}; + float m_actor_active_distance{2000.0}; + bool m_spectator_as_ego{true}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsCdrAux.hpp new file mode 100644 index 00000000000..5c72a469e79 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaEpisodeSettingsCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGSCDRAUX_HPP_ + +#include "CarlaEpisodeSettings.h" + +constexpr uint32_t carla_msgs_msg_CarlaEpisodeSettings_max_cdr_typesize {53UL}; +constexpr uint32_t carla_msgs_msg_CarlaEpisodeSettings_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEpisodeSettings& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsCdrAux.ipp new file mode 100644 index 00000000000..2fcacf85556 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsCdrAux.ipp @@ -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 CarlaEpisodeSettingsCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGSCDRAUX_IPP_ + +#include "CarlaEpisodeSettingsCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaEpisodeSettings& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.synchronous_mode(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.no_rendering_mode(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.fixed_delta_seconds(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.substepping(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.max_substep_delta_time(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.max_substeps(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.max_culling_distance(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.deterministic_ragdolls(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.tile_stream_distance(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), + data.actor_active_distance(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(10), + data.spectator_as_ego(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEpisodeSettings& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.synchronous_mode() + << eprosima::fastcdr::MemberId(1) << data.no_rendering_mode() + << eprosima::fastcdr::MemberId(2) << data.fixed_delta_seconds() + << eprosima::fastcdr::MemberId(3) << data.substepping() + << eprosima::fastcdr::MemberId(4) << data.max_substep_delta_time() + << eprosima::fastcdr::MemberId(5) << data.max_substeps() + << eprosima::fastcdr::MemberId(6) << data.max_culling_distance() + << eprosima::fastcdr::MemberId(7) << data.deterministic_ragdolls() + << eprosima::fastcdr::MemberId(8) << data.tile_stream_distance() + << eprosima::fastcdr::MemberId(9) << data.actor_active_distance() + << eprosima::fastcdr::MemberId(10) << data.spectator_as_ego() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaEpisodeSettings& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.synchronous_mode(); + break; + + case 1: + dcdr >> data.no_rendering_mode(); + break; + + case 2: + dcdr >> data.fixed_delta_seconds(); + break; + + case 3: + dcdr >> data.substepping(); + break; + + case 4: + dcdr >> data.max_substep_delta_time(); + break; + + case 5: + dcdr >> data.max_substeps(); + break; + + case 6: + dcdr >> data.max_culling_distance(); + break; + + case 7: + dcdr >> data.deterministic_ragdolls(); + break; + + case 8: + dcdr >> data.tile_stream_distance(); + break; + + case 9: + dcdr >> data.actor_active_distance(); + break; + + case 10: + dcdr >> data.spectator_as_ego(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaEpisodeSettings& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGSCDRAUX_IPP_ + 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..0246c355c2a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsPubSubTypes.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 CarlaEpisodeSettingsPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaEpisodeSettingsPubSubTypes.h" +#include "CarlaEpisodeSettingsCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaEpisodeSettingsPubSubType::CarlaEpisodeSettingsPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaEpisodeSettings_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaEpisodeSettings::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaEpisodeSettings_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaEpisodeSettingsPubSubType::~CarlaEpisodeSettingsPubSubType() +{ +} + +bool CarlaEpisodeSettingsPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaEpisodeSettingsPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaEpisodeSettingsPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..e5519120fd4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaEpisodeSettingsPubSubTypes.h @@ -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 CarlaEpisodeSettingsPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaEpisodeSettings.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaEpisodeSettingsPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEPISODESETTINGS_PUBSUBTYPES_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..9565afb3317 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEvent.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 CarlaLaneInvasionEvent.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + +namespace CarlaLaneInvasionEvent_Constants { + + +} // namespace CarlaLaneInvasionEvent_Constants + + + + +CarlaLaneInvasionEvent::CarlaLaneInvasionEvent() +{ +} + +CarlaLaneInvasionEvent::~CarlaLaneInvasionEvent() +{ +} + +CarlaLaneInvasionEvent::CarlaLaneInvasionEvent( + const CarlaLaneInvasionEvent& x) +{ + m_header = x.m_header; + m_crossed_lane_markings = x.m_crossed_lane_markings; +} + +CarlaLaneInvasionEvent::CarlaLaneInvasionEvent( + CarlaLaneInvasionEvent&& x) noexcept +{ + m_header = std::move(x.m_header); + m_crossed_lane_markings = std::move(x.m_crossed_lane_markings); +} + +CarlaLaneInvasionEvent& CarlaLaneInvasionEvent::operator =( + const CarlaLaneInvasionEvent& x) +{ + + m_header = x.m_header; + m_crossed_lane_markings = x.m_crossed_lane_markings; + return *this; +} + +CarlaLaneInvasionEvent& CarlaLaneInvasionEvent::operator =( + CarlaLaneInvasionEvent&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_crossed_lane_markings = std::move(x.m_crossed_lane_markings); + return *this; +} + +bool CarlaLaneInvasionEvent::operator ==( + const CarlaLaneInvasionEvent& x) const +{ + return (m_header == x.m_header && + m_crossed_lane_markings == x.m_crossed_lane_markings); +} + +bool CarlaLaneInvasionEvent::operator !=( + const CarlaLaneInvasionEvent& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& CarlaLaneInvasionEvent::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& 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 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 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& 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& CarlaLaneInvasionEvent::crossed_lane_markings() +{ + return m_crossed_lane_markings; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaLaneInvasionEventCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEvent.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEvent.h new file mode 100644 index 00000000000..a47a5c902a9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEvent.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 CarlaLaneInvasionEvent.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "std_msgs/msg/Header.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(CARLALANEINVASIONEVENT_SOURCE) +#define CARLALANEINVASIONEVENT_DllAPI __declspec( dllexport ) +#else +#define CARLALANEINVASIONEVENT_DllAPI __declspec( dllimport ) +#endif // CARLALANEINVASIONEVENT_SOURCE +#else +#define CARLALANEINVASIONEVENT_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLALANEINVASIONEVENT_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + +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 CarlaLaneInvasionEvent defined by the user in the IDL file. + * @ingroup CarlaLaneInvasionEvent + */ +class CarlaLaneInvasionEvent +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaLaneInvasionEvent(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaLaneInvasionEvent(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaLaneInvasionEvent that will be copied. + */ + eProsima_user_DllExport CarlaLaneInvasionEvent( + const CarlaLaneInvasionEvent& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaLaneInvasionEvent that will be copied. + */ + eProsima_user_DllExport CarlaLaneInvasionEvent( + CarlaLaneInvasionEvent&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaLaneInvasionEvent that will be copied. + */ + eProsima_user_DllExport CarlaLaneInvasionEvent& operator =( + const CarlaLaneInvasionEvent& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaLaneInvasionEvent that will be copied. + */ + eProsima_user_DllExport CarlaLaneInvasionEvent& operator =( + CarlaLaneInvasionEvent&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaLaneInvasionEvent object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaLaneInvasionEvent& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaLaneInvasionEvent object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaLaneInvasionEvent& 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(); + +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_CARLALANEINVASIONEVENT_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventCdrAux.hpp new file mode 100644 index 00000000000..0bd3e03e2f0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventCdrAux.hpp @@ -0,0 +1,60 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaLaneInvasionEventCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENTCDRAUX_HPP_ + +#include "CarlaLaneInvasionEvent.h" + +constexpr uint32_t carla_msgs_msg_CarlaLaneInvasionEvent_max_cdr_typesize {684UL}; +constexpr uint32_t carla_msgs_msg_CarlaLaneInvasionEvent_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaLaneInvasionEvent& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventCdrAux.ipp new file mode 100644 index 00000000000..5e4ded2cbbd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventCdrAux.ipp @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaLaneInvasionEventCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENTCDRAUX_IPP_ + +#include "CarlaLaneInvasionEventCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaLaneInvasionEvent& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.crossed_lane_markings(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaLaneInvasionEvent& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.crossed_lane_markings() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaLaneInvasionEvent& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.crossed_lane_markings(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaLaneInvasionEvent& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENTCDRAUX_IPP_ + 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..b64e630de11 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventPubSubTypes.cxx @@ -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 CarlaLaneInvasionEventPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaLaneInvasionEventPubSubTypes.h" +#include "CarlaLaneInvasionEventCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { +namespace CarlaLaneInvasionEvent_Constants { + + + + + + + +} //End of namespace CarlaLaneInvasionEvent_Constants + + + + + +CarlaLaneInvasionEventPubSubType::CarlaLaneInvasionEventPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaLaneInvasionEvent_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaLaneInvasionEvent::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaLaneInvasionEvent_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaLaneInvasionEventPubSubType::~CarlaLaneInvasionEventPubSubType() +{ +} + +bool CarlaLaneInvasionEventPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaLaneInvasionEventPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaLaneInvasionEventPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventPubSubTypes.h new file mode 100644 index 00000000000..80a5d3c02b5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaLaneInvasionEventPubSubTypes.h @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaLaneInvasionEvent.h" + +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + 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 { + + + + + + +} // namespace CarlaLaneInvasionEvent_Constants + + + + + +/*! + * @brief This class represents the TopicDataType of the type CarlaLaneInvasionEvent defined by the user in the IDL file. + * @ingroup CarlaLaneInvasionEvent + */ +class CarlaLaneInvasionEventPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaLaneInvasionEvent type; + + eProsima_user_DllExport CarlaLaneInvasionEventPubSubType(); + + eProsima_user_DllExport ~CarlaLaneInvasionEventPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALANEINVASIONEVENT_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..3f46db33e80 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatus.cxx @@ -0,0 +1,297 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaStatus::CarlaStatus() +{ +} + +CarlaStatus::~CarlaStatus() +{ +} + +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; +} + +CarlaStatus::CarlaStatus( + CarlaStatus&& x) noexcept +{ + 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; +} + +CarlaStatus& 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; +} + +CarlaStatus& CarlaStatus::operator =( + CarlaStatus&& x) noexcept +{ + + 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 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 CarlaStatus::operator !=( + const CarlaStatus& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& CarlaStatus::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& 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 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 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& 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& CarlaStatus::episode_settings() +{ + return m_episode_settings; +} + + +/*! + * @brief This function sets a value in member frame + * @param _frame New value for member frame + */ +void CarlaStatus::frame( + uint64_t _frame) +{ + m_frame = _frame; +} + +/*! + * @brief This function returns the value of member frame + * @return Value of member frame + */ +uint64_t CarlaStatus::frame() const +{ + return m_frame; +} + +/*! + * @brief This function returns a reference to member frame + * @return Reference to member frame + */ +uint64_t& 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 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 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& 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& 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 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 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& CarlaStatus::game_running() +{ + return m_game_running; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaStatusCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatus.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatus.h new file mode 100644 index 00000000000..369d7e84539 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatus.h @@ -0,0 +1,277 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CarlaSynchronizationWindowParticipantState.h" +#include "std_msgs/msg/Header.h" +#include "CarlaEpisodeSettings.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(CARLASTATUS_SOURCE) +#define CARLASTATUS_DllAPI __declspec( dllexport ) +#else +#define CARLASTATUS_DllAPI __declspec( dllimport ) +#endif // CARLASTATUS_SOURCE +#else +#define CARLASTATUS_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLASTATUS_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure CarlaStatus defined by the user in the IDL file. + * @ingroup CarlaStatus + */ +class CarlaStatus +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaStatus(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaStatus(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaStatus that will be copied. + */ + eProsima_user_DllExport CarlaStatus( + const CarlaStatus& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaStatus that will be copied. + */ + eProsima_user_DllExport CarlaStatus( + CarlaStatus&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaStatus that will be copied. + */ + eProsima_user_DllExport CarlaStatus& operator =( + const CarlaStatus& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaStatus that will be copied. + */ + eProsima_user_DllExport CarlaStatus& operator =( + CarlaStatus&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaStatus object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaStatus& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaStatus object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaStatus& 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 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 sets a value in member frame + * @param _frame New value for member frame + */ + eProsima_user_DllExport void frame( + uint64_t _frame); + + /*! + * @brief This function returns the value of member frame + * @return Value of member frame + */ + eProsima_user_DllExport uint64_t frame() const; + + /*! + * @brief This function returns a reference to member frame + * @return Reference to member frame + */ + eProsima_user_DllExport uint64_t& 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 + */ + eProsima_user_DllExport void synchronous_mode_participant_states( + const std::vector& _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 + */ + eProsima_user_DllExport void synchronous_mode_participant_states( + std::vector&& _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 + */ + eProsima_user_DllExport const std::vector& synchronous_mode_participant_states() const; + + /*! + * @brief This function returns a reference to member synchronous_mode_participant_states + * @return Reference to member synchronous_mode_participant_states + */ + eProsima_user_DllExport std::vector& synchronous_mode_participant_states(); + + + /*! + * @brief This function sets a value in member game_running + * @param _game_running New value for member game_running + */ + eProsima_user_DllExport void game_running( + bool _game_running); + + /*! + * @brief This function returns the value of member game_running + * @return Value of member game_running + */ + eProsima_user_DllExport bool game_running() const; + + /*! + * @brief This function returns a reference to member game_running + * @return Reference to member game_running + */ + eProsima_user_DllExport bool& game_running(); + +private: + + std_msgs::msg::Header m_header; + carla_msgs::msg::CarlaEpisodeSettings m_episode_settings; + uint64_t m_frame{0}; + std::vector m_synchronous_mode_participant_states; + bool m_game_running{false}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusCdrAux.hpp new file mode 100644 index 00000000000..b47c6ca83c9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaStatusCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUSCDRAUX_HPP_ + +#include "CarlaStatus.h" + +constexpr uint32_t carla_msgs_msg_CarlaStatus_max_cdr_typesize {28353UL}; +constexpr uint32_t carla_msgs_msg_CarlaStatus_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaStatus& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusCdrAux.ipp new file mode 100644 index 00000000000..9737b4f00d8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusCdrAux.ipp @@ -0,0 +1,162 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaStatusCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUSCDRAUX_IPP_ + +#include "CarlaStatusCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaStatus& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.episode_settings(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.frame(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.synchronous_mode_participant_states(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.game_running(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaStatus& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.episode_settings() + << eprosima::fastcdr::MemberId(2) << data.frame() + << eprosima::fastcdr::MemberId(3) << data.synchronous_mode_participant_states() + << eprosima::fastcdr::MemberId(4) << data.game_running() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaStatus& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.episode_settings(); + break; + + case 2: + dcdr >> data.frame(); + break; + + case 3: + dcdr >> data.synchronous_mode_participant_states(); + break; + + case 4: + dcdr >> data.game_running(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaStatus& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUSCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.cxx new file mode 100644 index 00000000000..dbfa9d0908c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.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 CarlaStatusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaStatusPubSubTypes.h" +#include "CarlaStatusCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaStatusPubSubType::CarlaStatusPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaStatus_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaStatus::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaStatus_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaStatusPubSubType::~CarlaStatusPubSubType() +{ +} + +bool CarlaStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CarlaStatus* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaStatusPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CarlaStatusPubSubType::createData() +{ + return reinterpret_cast(new CarlaStatus()); +} + +void CarlaStatusPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CarlaStatusPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.h new file mode 100644 index 00000000000..9619ff2d46f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaStatusPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaStatusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaStatus.h" + +#include "CarlaSynchronizationWindowParticipantStatePubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" +#include "CarlaEpisodeSettingsPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaStatus 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 CarlaStatus defined by the user in the IDL file. + * @ingroup CarlaStatus + */ +class CarlaStatusPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaStatus type; + + eProsima_user_DllExport CarlaStatusPubSubType(); + + eProsima_user_DllExport ~CarlaStatusPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASTATUS_PUBSUBTYPES_H_ + 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..cebc732b317 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindow.cxx @@ -0,0 +1,131 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaSynchronizationWindow::CarlaSynchronizationWindow() +{ +} + +CarlaSynchronizationWindow::~CarlaSynchronizationWindow() +{ +} + +CarlaSynchronizationWindow::CarlaSynchronizationWindow( + const CarlaSynchronizationWindow& x) +{ + m_synchronization_window_target_game_time = x.m_synchronization_window_target_game_time; +} + +CarlaSynchronizationWindow::CarlaSynchronizationWindow( + CarlaSynchronizationWindow&& x) noexcept +{ + m_synchronization_window_target_game_time = x.m_synchronization_window_target_game_time; +} + +CarlaSynchronizationWindow& CarlaSynchronizationWindow::operator =( + const CarlaSynchronizationWindow& x) +{ + + m_synchronization_window_target_game_time = x.m_synchronization_window_target_game_time; + return *this; +} + +CarlaSynchronizationWindow& CarlaSynchronizationWindow::operator =( + CarlaSynchronizationWindow&& x) noexcept +{ + + m_synchronization_window_target_game_time = x.m_synchronization_window_target_game_time; + return *this; +} + +bool CarlaSynchronizationWindow::operator ==( + const CarlaSynchronizationWindow& x) const +{ + return (m_synchronization_window_target_game_time == x.m_synchronization_window_target_game_time); +} + +bool CarlaSynchronizationWindow::operator !=( + const CarlaSynchronizationWindow& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& CarlaSynchronizationWindow::synchronization_window_target_game_time() +{ + return m_synchronization_window_target_game_time; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaSynchronizationWindowCdrAux.ipp" + 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..8483c2b0664 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindow.h @@ -0,0 +1,169 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_H_ + +#include +#include +#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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + float m_synchronization_window_target_game_time{0.0}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowCdrAux.hpp new file mode 100644 index 00000000000..1faab0e79f9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaSynchronizationWindowCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWCDRAUX_HPP_ + +#include "CarlaSynchronizationWindow.h" + +constexpr uint32_t carla_msgs_msg_CarlaSynchronizationWindow_max_cdr_typesize {8UL}; +constexpr uint32_t carla_msgs_msg_CarlaSynchronizationWindow_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaSynchronizationWindow& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowCdrAux.ipp new file mode 100644 index 00000000000..e1b418d04d6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowCdrAux.ipp @@ -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 CarlaSynchronizationWindowCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWCDRAUX_IPP_ + +#include "CarlaSynchronizationWindowCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaSynchronizationWindow& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.synchronization_window_target_game_time(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaSynchronizationWindow& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.synchronization_window_target_game_time() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaSynchronizationWindow& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.synchronization_window_target_game_time(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaSynchronizationWindow& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWCDRAUX_IPP_ + 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..d2f580cf455 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantState.cxx @@ -0,0 +1,209 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaSynchronizationWindowParticipantState::CarlaSynchronizationWindowParticipantState() +{ +} + +CarlaSynchronizationWindowParticipantState::~CarlaSynchronizationWindowParticipantState() +{ +} + +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; +} + +CarlaSynchronizationWindowParticipantState::CarlaSynchronizationWindowParticipantState( + CarlaSynchronizationWindowParticipantState&& x) noexcept +{ + 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; +} + +CarlaSynchronizationWindowParticipantState& 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; +} + +CarlaSynchronizationWindowParticipantState& CarlaSynchronizationWindowParticipantState::operator =( + CarlaSynchronizationWindowParticipantState&& x) noexcept +{ + + 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 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 CarlaSynchronizationWindowParticipantState::operator !=( + const CarlaSynchronizationWindowParticipantState& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member client_id + * @param _client_id New value to be copied in member client_id + */ +void 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 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& 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& 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 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 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& 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 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 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& CarlaSynchronizationWindowParticipantState::target_game_time() +{ + return m_target_game_time; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaSynchronizationWindowParticipantStateCdrAux.ipp" + 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..92002e722fd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantState.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 CarlaSynchronizationWindowParticipantState.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_H_ + +#include +#include +#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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::string m_client_id; + uint32_t m_participant_id{0}; + double m_target_game_time{0.0}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStateCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStateCdrAux.hpp new file mode 100644 index 00000000000..5afe8177b60 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStateCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaSynchronizationWindowParticipantStateCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATECDRAUX_HPP_ + +#include "CarlaSynchronizationWindowParticipantState.h" + +constexpr uint32_t carla_msgs_msg_CarlaSynchronizationWindowParticipantState_max_cdr_typesize {280UL}; +constexpr uint32_t carla_msgs_msg_CarlaSynchronizationWindowParticipantState_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaSynchronizationWindowParticipantState& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStateCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStateCdrAux.ipp new file mode 100644 index 00000000000..93f0343e25e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStateCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaSynchronizationWindowParticipantStateCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATECDRAUX_IPP_ + +#include "CarlaSynchronizationWindowParticipantStateCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaSynchronizationWindowParticipantState& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.client_id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.participant_id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.target_game_time(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaSynchronizationWindowParticipantState& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.client_id() + << eprosima::fastcdr::MemberId(1) << data.participant_id() + << eprosima::fastcdr::MemberId(2) << data.target_game_time() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaSynchronizationWindowParticipantState& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.client_id(); + break; + + case 1: + dcdr >> data.participant_id(); + break; + + case 2: + dcdr >> data.target_game_time(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaSynchronizationWindowParticipantState& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATECDRAUX_IPP_ + 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..1a280e5c54b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStatePubSubTypes.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 CarlaSynchronizationWindowParticipantStatePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaSynchronizationWindowParticipantStatePubSubTypes.h" +#include "CarlaSynchronizationWindowParticipantStateCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaSynchronizationWindowParticipantStatePubSubType::CarlaSynchronizationWindowParticipantStatePubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaSynchronizationWindowParticipantState_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaSynchronizationWindowParticipantState::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaSynchronizationWindowParticipantState_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaSynchronizationWindowParticipantStatePubSubType::~CarlaSynchronizationWindowParticipantStatePubSubType() +{ +} + +bool CarlaSynchronizationWindowParticipantStatePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaSynchronizationWindowParticipantStatePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaSynchronizationWindowParticipantStatePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..745f2d68aa7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowParticipantStatePubSubTypes.h @@ -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 CarlaSynchronizationWindowParticipantStatePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaSynchronizationWindowParticipantState.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaSynchronizationWindowParticipantStatePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOWPARTICIPANTSTATE_PUBSUBTYPES_H_ + 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..c7780e41d69 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowPubSubTypes.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 CarlaSynchronizationWindowPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaSynchronizationWindowPubSubTypes.h" +#include "CarlaSynchronizationWindowCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaSynchronizationWindowPubSubType::CarlaSynchronizationWindowPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaSynchronizationWindow_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaSynchronizationWindow::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaSynchronizationWindow_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaSynchronizationWindowPubSubType::~CarlaSynchronizationWindowPubSubType() +{ +} + +bool CarlaSynchronizationWindowPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaSynchronizationWindowPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaSynchronizationWindowPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..c9ffdf1081c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaSynchronizationWindowPubSubTypes.h @@ -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 CarlaSynchronizationWindowPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaSynchronizationWindow.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaSynchronizationWindowPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLASYNCHRONIZATIONWINDOW_PUBSUBTYPES_H_ + 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..884c77e172a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfo.cxx @@ -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 CarlaTrafficLightInfo.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaTrafficLightInfo::CarlaTrafficLightInfo() +{ +} + +CarlaTrafficLightInfo::~CarlaTrafficLightInfo() +{ +} + +CarlaTrafficLightInfo::CarlaTrafficLightInfo( + const CarlaTrafficLightInfo& x) +{ + m_id = x.m_id; + m_transform = x.m_transform; + m_trigger_volume = x.m_trigger_volume; +} + +CarlaTrafficLightInfo::CarlaTrafficLightInfo( + CarlaTrafficLightInfo&& x) noexcept +{ + m_id = x.m_id; + m_transform = std::move(x.m_transform); + m_trigger_volume = std::move(x.m_trigger_volume); +} + +CarlaTrafficLightInfo& CarlaTrafficLightInfo::operator =( + const CarlaTrafficLightInfo& x) +{ + + m_id = x.m_id; + m_transform = x.m_transform; + m_trigger_volume = x.m_trigger_volume; + return *this; +} + +CarlaTrafficLightInfo& CarlaTrafficLightInfo::operator =( + CarlaTrafficLightInfo&& x) noexcept +{ + + m_id = x.m_id; + m_transform = std::move(x.m_transform); + m_trigger_volume = std::move(x.m_trigger_volume); + return *this; +} + +bool 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 CarlaTrafficLightInfo::operator !=( + const CarlaTrafficLightInfo& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void CarlaTrafficLightInfo::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t CarlaTrafficLightInfo::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& 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 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 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& CarlaTrafficLightInfo::transform() const +{ + return m_transform; +} + +/*! + * @brief This function returns a reference to member transform + * @return Reference to member transform + */ +geometry_msgs::msg::Pose& 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 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 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& 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& CarlaTrafficLightInfo::trigger_volume() +{ + return m_trigger_volume; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaTrafficLightInfoCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfo.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfo.h new file mode 100644 index 00000000000..4c7b34aee07 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfo.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 CarlaTrafficLightInfo.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CarlaBoundingBox.h" +#include "geometry_msgs/msg/Pose.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(CARLATRAFFICLIGHTINFO_SOURCE) +#define CARLATRAFFICLIGHTINFO_DllAPI __declspec( dllexport ) +#else +#define CARLATRAFFICLIGHTINFO_DllAPI __declspec( dllimport ) +#endif // CARLATRAFFICLIGHTINFO_SOURCE +#else +#define CARLATRAFFICLIGHTINFO_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLATRAFFICLIGHTINFO_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure CarlaTrafficLightInfo defined by the user in the IDL file. + * @ingroup CarlaTrafficLightInfo + */ +class CarlaTrafficLightInfo +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaTrafficLightInfo(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaTrafficLightInfo(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfo that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightInfo( + const CarlaTrafficLightInfo& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfo that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightInfo( + CarlaTrafficLightInfo&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfo that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightInfo& operator =( + const CarlaTrafficLightInfo& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightInfo that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightInfo& operator =( + CarlaTrafficLightInfo&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaTrafficLightInfo object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaTrafficLightInfo& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaTrafficLightInfo object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaTrafficLightInfo& 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 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 copies the value in member trigger_volume + * @param _trigger_volume New value to be copied in member trigger_volume + */ + eProsima_user_DllExport void trigger_volume( + const carla_msgs::msg::CarlaBoundingBox& _trigger_volume); + + /*! + * @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 void trigger_volume( + carla_msgs::msg::CarlaBoundingBox&& _trigger_volume); + + /*! + * @brief This function returns a constant reference to member trigger_volume + * @return Constant reference to member trigger_volume + */ + eProsima_user_DllExport const carla_msgs::msg::CarlaBoundingBox& trigger_volume() const; + + /*! + * @brief This function returns a reference to member trigger_volume + * @return Reference to member trigger_volume + */ + eProsima_user_DllExport carla_msgs::msg::CarlaBoundingBox& trigger_volume(); + +private: + + uint32_t m_id{0}; + geometry_msgs::msg::Pose m_transform; + carla_msgs::msg::CarlaBoundingBox m_trigger_volume; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoCdrAux.hpp new file mode 100644 index 00000000000..0ecece2a533 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaTrafficLightInfoCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOCDRAUX_HPP_ + +#include "CarlaTrafficLightInfo.h" + +constexpr uint32_t carla_msgs_msg_CarlaTrafficLightInfo_max_cdr_typesize {144UL}; +constexpr uint32_t carla_msgs_msg_CarlaTrafficLightInfo_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightInfo& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoCdrAux.ipp new file mode 100644 index 00000000000..235e3304223 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaTrafficLightInfoCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOCDRAUX_IPP_ + +#include "CarlaTrafficLightInfoCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaTrafficLightInfo& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.transform(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.trigger_volume(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightInfo& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.id() + << eprosima::fastcdr::MemberId(1) << data.transform() + << eprosima::fastcdr::MemberId(2) << data.trigger_volume() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaTrafficLightInfo& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.id(); + break; + + case 1: + dcdr >> data.transform(); + break; + + case 2: + dcdr >> data.trigger_volume(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightInfo& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOCDRAUX_IPP_ + 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..377afff7791 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoList.cxx @@ -0,0 +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 CarlaTrafficLightInfoList.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + + + +CarlaTrafficLightInfoList::CarlaTrafficLightInfoList() +{ +} + +CarlaTrafficLightInfoList::~CarlaTrafficLightInfoList() +{ +} + +CarlaTrafficLightInfoList::CarlaTrafficLightInfoList( + const CarlaTrafficLightInfoList& x) +{ + m_traffic_lights = x.m_traffic_lights; +} + +CarlaTrafficLightInfoList::CarlaTrafficLightInfoList( + CarlaTrafficLightInfoList&& x) noexcept +{ + m_traffic_lights = std::move(x.m_traffic_lights); +} + +CarlaTrafficLightInfoList& CarlaTrafficLightInfoList::operator =( + const CarlaTrafficLightInfoList& x) +{ + + m_traffic_lights = x.m_traffic_lights; + return *this; +} + +CarlaTrafficLightInfoList& CarlaTrafficLightInfoList::operator =( + CarlaTrafficLightInfoList&& x) noexcept +{ + + m_traffic_lights = std::move(x.m_traffic_lights); + return *this; +} + +bool CarlaTrafficLightInfoList::operator ==( + const CarlaTrafficLightInfoList& x) const +{ + return (m_traffic_lights == x.m_traffic_lights); +} + +bool CarlaTrafficLightInfoList::operator !=( + const CarlaTrafficLightInfoList& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member traffic_lights + * @param _traffic_lights New value to be copied in member traffic_lights + */ +void 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 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& 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& CarlaTrafficLightInfoList::traffic_lights() +{ + return m_traffic_lights; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaTrafficLightInfoListCdrAux.ipp" + 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..9970f7d0ba0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoList.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CarlaTrafficLightInfo.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_traffic_lights; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListCdrAux.hpp new file mode 100644 index 00000000000..d270b57bf87 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListCdrAux.hpp @@ -0,0 +1,54 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaTrafficLightInfoListCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLISTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLISTCDRAUX_HPP_ + +#include "CarlaTrafficLightInfoList.h" + +constexpr uint32_t carla_msgs_msg_CarlaTrafficLightInfoList_max_cdr_typesize {14416UL}; +constexpr uint32_t carla_msgs_msg_CarlaTrafficLightInfoList_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightInfoList& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLISTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListCdrAux.ipp new file mode 100644 index 00000000000..901821e32e4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListCdrAux.ipp @@ -0,0 +1,132 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaTrafficLightInfoListCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLISTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLISTCDRAUX_IPP_ + +#include "CarlaTrafficLightInfoListCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaTrafficLightInfoList& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.traffic_lights(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightInfoList& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.traffic_lights() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaTrafficLightInfoList& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.traffic_lights(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightInfoList& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLISTCDRAUX_IPP_ + 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..cc1be3971c4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListPubSubTypes.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 CarlaTrafficLightInfoListPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaTrafficLightInfoListPubSubTypes.h" +#include "CarlaTrafficLightInfoListCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + + + +CarlaTrafficLightInfoListPubSubType::CarlaTrafficLightInfoListPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaTrafficLightInfoList_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaTrafficLightInfoList::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaTrafficLightInfoList_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaTrafficLightInfoListPubSubType::~CarlaTrafficLightInfoListPubSubType() +{ +} + +bool CarlaTrafficLightInfoListPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaTrafficLightInfoListPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaTrafficLightInfoListPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..bcb2c282436 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoListPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaTrafficLightInfoList.h" + +#include "CarlaTrafficLightInfoPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaTrafficLightInfoListPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFOLIST_PUBSUBTYPES_H_ + 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..ab684ccba26 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoPubSubTypes.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 CarlaTrafficLightInfoPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaTrafficLightInfoPubSubTypes.h" +#include "CarlaTrafficLightInfoCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaTrafficLightInfoPubSubType::CarlaTrafficLightInfoPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaTrafficLightInfo_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaTrafficLightInfo::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaTrafficLightInfo_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaTrafficLightInfoPubSubType::~CarlaTrafficLightInfoPubSubType() +{ +} + +bool CarlaTrafficLightInfoPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaTrafficLightInfoPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaTrafficLightInfoPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..fc2c3697bee --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightInfoPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaTrafficLightInfo.h" + +#include "CarlaBoundingBoxPubSubTypes.h" +#include "geometry_msgs/msg/PosePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaTrafficLightInfoPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTINFO_PUBSUBTYPES_H_ + 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..d4b21c7ae6f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatus.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 CarlaTrafficLightStatus.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + +namespace CarlaTrafficLightStatus_Constants { + + +} // namespace CarlaTrafficLightStatus_Constants + + +CarlaTrafficLightStatus::CarlaTrafficLightStatus() +{ +} + +CarlaTrafficLightStatus::~CarlaTrafficLightStatus() +{ +} + +CarlaTrafficLightStatus::CarlaTrafficLightStatus( + const CarlaTrafficLightStatus& x) +{ + m_header = x.m_header; + m_id = x.m_id; + m_state = x.m_state; +} + +CarlaTrafficLightStatus::CarlaTrafficLightStatus( + CarlaTrafficLightStatus&& x) noexcept +{ + m_header = std::move(x.m_header); + m_id = x.m_id; + m_state = x.m_state; +} + +CarlaTrafficLightStatus& CarlaTrafficLightStatus::operator =( + const CarlaTrafficLightStatus& x) +{ + + m_header = x.m_header; + m_id = x.m_id; + m_state = x.m_state; + return *this; +} + +CarlaTrafficLightStatus& CarlaTrafficLightStatus::operator =( + CarlaTrafficLightStatus&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_id = x.m_id; + m_state = x.m_state; + return *this; +} + +bool CarlaTrafficLightStatus::operator ==( + const CarlaTrafficLightStatus& x) const +{ + return (m_header == x.m_header && + m_id == x.m_id && + m_state == x.m_state); +} + +bool CarlaTrafficLightStatus::operator !=( + const CarlaTrafficLightStatus& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& CarlaTrafficLightStatus::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& CarlaTrafficLightStatus::header() +{ + return m_header; +} + + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void CarlaTrafficLightStatus::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t CarlaTrafficLightStatus::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& CarlaTrafficLightStatus::id() +{ + return m_id; +} + + +/*! + * @brief This function sets a value in member state + * @param _state New value for member state + */ +void CarlaTrafficLightStatus::state( + uint8_t _state) +{ + m_state = _state; +} + +/*! + * @brief This function returns the value of member state + * @return Value of member state + */ +uint8_t CarlaTrafficLightStatus::state() const +{ + return m_state; +} + +/*! + * @brief This function returns a reference to member state + * @return Reference to member state + */ +uint8_t& CarlaTrafficLightStatus::state() +{ + return m_state; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaTrafficLightStatusCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatus.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatus.h new file mode 100644 index 00000000000..24659ad6e31 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatus.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 CarlaTrafficLightStatus.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "std_msgs/msg/Header.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(CARLATRAFFICLIGHTSTATUS_SOURCE) +#define CARLATRAFFICLIGHTSTATUS_DllAPI __declspec( dllexport ) +#else +#define CARLATRAFFICLIGHTSTATUS_DllAPI __declspec( dllimport ) +#endif // CARLATRAFFICLIGHTSTATUS_SOURCE +#else +#define CARLATRAFFICLIGHTSTATUS_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLATRAFFICLIGHTSTATUS_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +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 CarlaTrafficLightStatus defined by the user in the IDL file. + * @ingroup CarlaTrafficLightStatus + */ +class CarlaTrafficLightStatus +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaTrafficLightStatus(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaTrafficLightStatus(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatus that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightStatus( + const CarlaTrafficLightStatus& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatus that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightStatus( + CarlaTrafficLightStatus&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatus that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightStatus& operator =( + const CarlaTrafficLightStatus& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaTrafficLightStatus that will be copied. + */ + eProsima_user_DllExport CarlaTrafficLightStatus& operator =( + CarlaTrafficLightStatus&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaTrafficLightStatus object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaTrafficLightStatus& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaTrafficLightStatus object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaTrafficLightStatus& 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 state + * @param _state New value for member state + */ + eProsima_user_DllExport void state( + uint8_t _state); + + /*! + * @brief This function returns the value of member state + * @return Value of member state + */ + eProsima_user_DllExport uint8_t state() const; + + /*! + * @brief This function returns a reference to member state + * @return Reference to member state + */ + eProsima_user_DllExport uint8_t& state(); + +private: + + std_msgs::msg::Header m_header; + uint32_t m_id{0}; + uint8_t m_state{0}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusCdrAux.hpp new file mode 100644 index 00000000000..5fbbcbff3b0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusCdrAux.hpp @@ -0,0 +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 CarlaTrafficLightStatusCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSCDRAUX_HPP_ + +#include "CarlaTrafficLightStatus.h" + +constexpr uint32_t carla_msgs_msg_CarlaTrafficLightStatus_max_cdr_typesize {285UL}; +constexpr uint32_t carla_msgs_msg_CarlaTrafficLightStatus_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightStatus& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusCdrAux.ipp new file mode 100644 index 00000000000..2ee59cf9795 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusCdrAux.ipp @@ -0,0 +1,157 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaTrafficLightStatusCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSCDRAUX_IPP_ + +#include "CarlaTrafficLightStatusCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaTrafficLightStatus& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.state(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightStatus& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.id() + << eprosima::fastcdr::MemberId(2) << data.state() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaTrafficLightStatus& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.id(); + break; + + case 2: + dcdr >> data.state(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightStatus& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSCDRAUX_IPP_ + 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..b0f85bb9aee --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusList.cxx @@ -0,0 +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 CarlaTrafficLightStatusList.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + + + +CarlaTrafficLightStatusList::CarlaTrafficLightStatusList() +{ +} + +CarlaTrafficLightStatusList::~CarlaTrafficLightStatusList() +{ +} + +CarlaTrafficLightStatusList::CarlaTrafficLightStatusList( + const CarlaTrafficLightStatusList& x) +{ + m_traffic_lights = x.m_traffic_lights; +} + +CarlaTrafficLightStatusList::CarlaTrafficLightStatusList( + CarlaTrafficLightStatusList&& x) noexcept +{ + m_traffic_lights = std::move(x.m_traffic_lights); +} + +CarlaTrafficLightStatusList& CarlaTrafficLightStatusList::operator =( + const CarlaTrafficLightStatusList& x) +{ + + m_traffic_lights = x.m_traffic_lights; + return *this; +} + +CarlaTrafficLightStatusList& CarlaTrafficLightStatusList::operator =( + CarlaTrafficLightStatusList&& x) noexcept +{ + + m_traffic_lights = std::move(x.m_traffic_lights); + return *this; +} + +bool CarlaTrafficLightStatusList::operator ==( + const CarlaTrafficLightStatusList& x) const +{ + return (m_traffic_lights == x.m_traffic_lights); +} + +bool CarlaTrafficLightStatusList::operator !=( + const CarlaTrafficLightStatusList& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member traffic_lights + * @param _traffic_lights New value to be copied in member traffic_lights + */ +void 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 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& 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& CarlaTrafficLightStatusList::traffic_lights() +{ + return m_traffic_lights; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaTrafficLightStatusListCdrAux.ipp" + 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..e029ab64e35 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusList.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CarlaTrafficLightStatus.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_traffic_lights; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListCdrAux.hpp new file mode 100644 index 00000000000..d217f600e7c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListCdrAux.hpp @@ -0,0 +1,54 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaTrafficLightStatusListCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLISTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLISTCDRAUX_HPP_ + +#include "CarlaTrafficLightStatusList.h" + +constexpr uint32_t carla_msgs_msg_CarlaTrafficLightStatusList_max_cdr_typesize {28809UL}; +constexpr uint32_t carla_msgs_msg_CarlaTrafficLightStatusList_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightStatusList& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLISTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListCdrAux.ipp new file mode 100644 index 00000000000..0d531791fb3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListCdrAux.ipp @@ -0,0 +1,132 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaTrafficLightStatusListCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLISTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLISTCDRAUX_IPP_ + +#include "CarlaTrafficLightStatusListCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaTrafficLightStatusList& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.traffic_lights(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightStatusList& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.traffic_lights() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaTrafficLightStatusList& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.traffic_lights(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaTrafficLightStatusList& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLISTCDRAUX_IPP_ + 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..055c9a48324 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListPubSubTypes.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 CarlaTrafficLightStatusListPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaTrafficLightStatusListPubSubTypes.h" +#include "CarlaTrafficLightStatusListCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + + + +CarlaTrafficLightStatusListPubSubType::CarlaTrafficLightStatusListPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaTrafficLightStatusList_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaTrafficLightStatusList::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaTrafficLightStatusList_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaTrafficLightStatusListPubSubType::~CarlaTrafficLightStatusListPubSubType() +{ +} + +bool CarlaTrafficLightStatusListPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaTrafficLightStatusListPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaTrafficLightStatusListPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..76051662e1a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusListPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaTrafficLightStatusList.h" + +#include "CarlaTrafficLightStatusPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaTrafficLightStatusListPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUSLIST_PUBSUBTYPES_H_ + 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..c42bce0d454 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusPubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaTrafficLightStatusPubSubTypes.h" +#include "CarlaTrafficLightStatusCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { +namespace CarlaTrafficLightStatus_Constants { + + + + + + + + + + + +} //End of namespace CarlaTrafficLightStatus_Constants + + + +CarlaTrafficLightStatusPubSubType::CarlaTrafficLightStatusPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaTrafficLightStatus_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaTrafficLightStatus::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaTrafficLightStatus_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaTrafficLightStatusPubSubType::~CarlaTrafficLightStatusPubSubType() +{ +} + +bool CarlaTrafficLightStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaTrafficLightStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaTrafficLightStatusPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..6871d6a379e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaTrafficLightStatusPubSubTypes.h @@ -0,0 +1,148 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaTrafficLightStatus.h" + +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~CarlaTrafficLightStatusPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLATRAFFICLIGHTSTATUS_PUBSUBTYPES_H_ + 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..e4c61c2466e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArray.cxx @@ -0,0 +1,175 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaV2XByteArray::CarlaV2XByteArray() +{ +} + +CarlaV2XByteArray::~CarlaV2XByteArray() +{ +} + +CarlaV2XByteArray::CarlaV2XByteArray( + const CarlaV2XByteArray& x) +{ + m_data_size = x.m_data_size; + m_bytes = x.m_bytes; +} + +CarlaV2XByteArray::CarlaV2XByteArray( + CarlaV2XByteArray&& x) noexcept +{ + m_data_size = x.m_data_size; + m_bytes = std::move(x.m_bytes); +} + +CarlaV2XByteArray& CarlaV2XByteArray::operator =( + const CarlaV2XByteArray& x) +{ + + m_data_size = x.m_data_size; + m_bytes = x.m_bytes; + return *this; +} + +CarlaV2XByteArray& CarlaV2XByteArray::operator =( + CarlaV2XByteArray&& x) noexcept +{ + + m_data_size = x.m_data_size; + m_bytes = std::move(x.m_bytes); + return *this; +} + +bool CarlaV2XByteArray::operator ==( + const CarlaV2XByteArray& x) const +{ + return (m_data_size == x.m_data_size && + m_bytes == x.m_bytes); +} + +bool CarlaV2XByteArray::operator !=( + const CarlaV2XByteArray& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member data_size + * @param _data_size New value for member data_size + */ +void 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 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& 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 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 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& 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& CarlaV2XByteArray::bytes() +{ + return m_bytes; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaV2XByteArrayCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArray.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArray.h new file mode 100644 index 00000000000..7a071a0b77e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArray.h @@ -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 CarlaV2XByteArray.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_H_ + +#include +#include +#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(CARLAV2XBYTEARRAY_SOURCE) +#define CARLAV2XBYTEARRAY_DllAPI __declspec( dllexport ) +#else +#define CARLAV2XBYTEARRAY_DllAPI __declspec( dllimport ) +#endif // CARLAV2XBYTEARRAY_SOURCE +#else +#define CARLAV2XBYTEARRAY_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLAV2XBYTEARRAY_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + +typedef std::array octet__100; + + + +/*! + * @brief This class represents the structure CarlaV2XByteArray defined by the user in the IDL file. + * @ingroup CarlaV2XByteArray + */ +class CarlaV2XByteArray +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaV2XByteArray(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaV2XByteArray(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XByteArray that will be copied. + */ + eProsima_user_DllExport CarlaV2XByteArray( + const CarlaV2XByteArray& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XByteArray that will be copied. + */ + eProsima_user_DllExport CarlaV2XByteArray( + CarlaV2XByteArray&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XByteArray that will be copied. + */ + eProsima_user_DllExport CarlaV2XByteArray& operator =( + const CarlaV2XByteArray& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XByteArray that will be copied. + */ + eProsima_user_DllExport CarlaV2XByteArray& operator =( + CarlaV2XByteArray&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XByteArray object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaV2XByteArray& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XByteArray object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaV2XByteArray& x) const; + + /*! + * @brief This function sets a value in member data_size + * @param _data_size New value for member data_size + */ + eProsima_user_DllExport void data_size( + uint8_t _data_size); + + /*! + * @brief This function returns the value of member data_size + * @return Value of member data_size + */ + eProsima_user_DllExport uint8_t data_size() const; + + /*! + * @brief This function returns a reference to member data_size + * @return Reference to member data_size + */ + eProsima_user_DllExport uint8_t& data_size(); + + + /*! + * @brief This function copies the value in member bytes + * @param _bytes New value to be copied in member bytes + */ + eProsima_user_DllExport void bytes( + const carla_msgs::msg::octet__100& _bytes); + + /*! + * @brief This function moves the value in member bytes + * @param _bytes New value to be moved in member bytes + */ + eProsima_user_DllExport void bytes( + carla_msgs::msg::octet__100&& _bytes); + + /*! + * @brief This function returns a constant reference to member bytes + * @return Constant reference to member bytes + */ + eProsima_user_DllExport const carla_msgs::msg::octet__100& bytes() const; + + /*! + * @brief This function returns a reference to member bytes + * @return Reference to member bytes + */ + eProsima_user_DllExport carla_msgs::msg::octet__100& bytes(); + +private: + + uint8_t m_data_size{0}; + carla_msgs::msg::octet__100 m_bytes{0}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayCdrAux.hpp new file mode 100644 index 00000000000..5c50e1cb184 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayCdrAux.hpp @@ -0,0 +1,53 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XByteArrayCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAYCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAYCDRAUX_HPP_ + +#include "CarlaV2XByteArray.h" + +constexpr uint32_t carla_msgs_msg_CarlaV2XByteArray_max_cdr_typesize {105UL}; +constexpr uint32_t carla_msgs_msg_CarlaV2XByteArray_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XByteArray& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAYCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayCdrAux.ipp new file mode 100644 index 00000000000..4e62f1401d1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayCdrAux.ipp @@ -0,0 +1,140 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XByteArrayCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAYCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAYCDRAUX_IPP_ + +#include "CarlaV2XByteArrayCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaV2XByteArray& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.data_size(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.bytes(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XByteArray& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.data_size() + << eprosima::fastcdr::MemberId(1) << data.bytes() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaV2XByteArray& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.data_size(); + break; + + case 1: + dcdr >> data.bytes(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XByteArray& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAYCDRAUX_IPP_ + 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..31086ef5b74 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayPubSubTypes.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 CarlaV2XByteArrayPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaV2XByteArrayPubSubTypes.h" +#include "CarlaV2XByteArrayCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + + + +CarlaV2XByteArrayPubSubType::CarlaV2XByteArrayPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaV2XByteArray_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaV2XByteArray::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaV2XByteArray_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaV2XByteArrayPubSubType::~CarlaV2XByteArrayPubSubType() +{ +} + +bool CarlaV2XByteArrayPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaV2XByteArrayPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaV2XByteArrayPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..de35164add3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XByteArrayPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaV2XByteArray.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaV2XByteArrayPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XBYTEARRAY_PUBSUBTYPES_H_ + 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..87b7f8cf186 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomData.cxx @@ -0,0 +1,175 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaV2XCustomData::CarlaV2XCustomData() +{ +} + +CarlaV2XCustomData::~CarlaV2XCustomData() +{ +} + +CarlaV2XCustomData::CarlaV2XCustomData( + const CarlaV2XCustomData& x) +{ + m_power = x.m_power; + m_message = x.m_message; +} + +CarlaV2XCustomData::CarlaV2XCustomData( + CarlaV2XCustomData&& x) noexcept +{ + m_power = x.m_power; + m_message = std::move(x.m_message); +} + +CarlaV2XCustomData& CarlaV2XCustomData::operator =( + const CarlaV2XCustomData& x) +{ + + m_power = x.m_power; + m_message = x.m_message; + return *this; +} + +CarlaV2XCustomData& CarlaV2XCustomData::operator =( + CarlaV2XCustomData&& x) noexcept +{ + + m_power = x.m_power; + m_message = std::move(x.m_message); + return *this; +} + +bool CarlaV2XCustomData::operator ==( + const CarlaV2XCustomData& x) const +{ + return (m_power == x.m_power && + m_message == x.m_message); +} + +bool CarlaV2XCustomData::operator !=( + const CarlaV2XCustomData& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member power + * @param _power New value for member power + */ +void CarlaV2XCustomData::power( + float _power) +{ + m_power = _power; +} + +/*! + * @brief This function returns the value of member power + * @return Value of member power + */ +float CarlaV2XCustomData::power() const +{ + return m_power; +} + +/*! + * @brief This function returns a reference to member power + * @return Reference to member power + */ +float& 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 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 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& CarlaV2XCustomData::message() const +{ + return m_message; +} + +/*! + * @brief This function returns a reference to member message + * @return Reference to member message + */ +carla_msgs::msg::CarlaV2XCustomMessage& CarlaV2XCustomData::message() +{ + return m_message; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaV2XCustomDataCdrAux.ipp" + 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..a0fb0a0b270 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomData.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 CarlaV2XCustomData.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CarlaV2XCustomMessage.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + float m_power{0.0}; + carla_msgs::msg::CarlaV2XCustomMessage m_message; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataCdrAux.hpp new file mode 100644 index 00000000000..c13d8a38c84 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataCdrAux.hpp @@ -0,0 +1,54 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XCustomDataCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATACDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATACDRAUX_HPP_ + +#include "CarlaV2XCustomData.h" + +constexpr uint32_t carla_msgs_msg_CarlaV2XCustomData_max_cdr_typesize {133UL}; +constexpr uint32_t carla_msgs_msg_CarlaV2XCustomData_max_key_cdr_typesize {0UL}; + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XCustomData& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATACDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataCdrAux.ipp new file mode 100644 index 00000000000..0fe5f44a10f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XCustomDataCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATACDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATACDRAUX_IPP_ + +#include "CarlaV2XCustomDataCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaV2XCustomData& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.power(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.message(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XCustomData& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.power() + << eprosima::fastcdr::MemberId(1) << data.message() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaV2XCustomData& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.power(); + break; + + case 1: + dcdr >> data.message(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XCustomData& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATACDRAUX_IPP_ + 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..f5a0ee05f84 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataList.cxx @@ -0,0 +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 CarlaV2XCustomDataList.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + + + +CarlaV2XCustomDataList::CarlaV2XCustomDataList() +{ +} + +CarlaV2XCustomDataList::~CarlaV2XCustomDataList() +{ +} + +CarlaV2XCustomDataList::CarlaV2XCustomDataList( + const CarlaV2XCustomDataList& x) +{ + m_data = x.m_data; +} + +CarlaV2XCustomDataList::CarlaV2XCustomDataList( + CarlaV2XCustomDataList&& x) noexcept +{ + m_data = std::move(x.m_data); +} + +CarlaV2XCustomDataList& CarlaV2XCustomDataList::operator =( + const CarlaV2XCustomDataList& x) +{ + + m_data = x.m_data; + return *this; +} + +CarlaV2XCustomDataList& CarlaV2XCustomDataList::operator =( + CarlaV2XCustomDataList&& x) noexcept +{ + + m_data = std::move(x.m_data); + return *this; +} + +bool CarlaV2XCustomDataList::operator ==( + const CarlaV2XCustomDataList& x) const +{ + return (m_data == x.m_data); +} + +bool CarlaV2XCustomDataList::operator !=( + const CarlaV2XCustomDataList& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ +void 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 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& CarlaV2XCustomDataList::data() const +{ + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +std::vector& CarlaV2XCustomDataList::data() +{ + return m_data; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaV2XCustomDataListCdrAux.ipp" + 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..1cc9be9d3df --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataList.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CarlaV2XCustomData.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_data; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListCdrAux.hpp new file mode 100644 index 00000000000..873e0c0393b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XCustomDataListCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALISTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALISTCDRAUX_HPP_ + +#include "CarlaV2XCustomDataList.h" + +constexpr uint32_t carla_msgs_msg_CarlaV2XCustomDataList_max_cdr_typesize {13609UL}; +constexpr uint32_t carla_msgs_msg_CarlaV2XCustomDataList_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XCustomDataList& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALISTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListCdrAux.ipp new file mode 100644 index 00000000000..78cc6d3388f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListCdrAux.ipp @@ -0,0 +1,132 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XCustomDataListCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALISTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALISTCDRAUX_IPP_ + +#include "CarlaV2XCustomDataListCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaV2XCustomDataList& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.data(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XCustomDataList& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.data() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaV2XCustomDataList& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.data(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XCustomDataList& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALISTCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.cxx new file mode 100644 index 00000000000..042edb61e32 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.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 CarlaV2XCustomDataListPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaV2XCustomDataListPubSubTypes.h" +#include "CarlaV2XCustomDataListCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + + + +CarlaV2XCustomDataListPubSubType::CarlaV2XCustomDataListPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaV2XCustomDataList_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaV2XCustomDataList::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaV2XCustomDataList_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaV2XCustomDataListPubSubType::~CarlaV2XCustomDataListPubSubType() +{ +} + +bool CarlaV2XCustomDataListPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CarlaV2XCustomDataList* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaV2XCustomDataListPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaV2XCustomDataListPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CarlaV2XCustomDataListPubSubType::createData() +{ + return reinterpret_cast(new CarlaV2XCustomDataList()); +} + +void CarlaV2XCustomDataListPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CarlaV2XCustomDataListPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..39e6a571979 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataListPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaV2XCustomDataList.h" + +#include "CarlaV2XCustomDataPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaV2XCustomDataListPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATALIST_PUBSUBTYPES_H_ + 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..f675c35522c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataPubSubTypes.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 CarlaV2XCustomDataPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaV2XCustomDataPubSubTypes.h" +#include "CarlaV2XCustomDataCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaV2XCustomDataPubSubType::CarlaV2XCustomDataPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaV2XCustomData_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaV2XCustomData::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaV2XCustomData_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaV2XCustomDataPubSubType::~CarlaV2XCustomDataPubSubType() +{ +} + +bool CarlaV2XCustomDataPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaV2XCustomDataPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaV2XCustomDataPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..efdaeea27d5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomDataPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaV2XCustomData.h" + +#include "CarlaV2XCustomMessagePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaV2XCustomDataPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMDATA_PUBSUBTYPES_H_ + 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..74331a63d61 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessage.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 CarlaV2XCustomMessage.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaV2XCustomMessage::CarlaV2XCustomMessage() +{ +} + +CarlaV2XCustomMessage::~CarlaV2XCustomMessage() +{ +} + +CarlaV2XCustomMessage::CarlaV2XCustomMessage( + const CarlaV2XCustomMessage& x) +{ + m_header = x.m_header; + m_data = x.m_data; +} + +CarlaV2XCustomMessage::CarlaV2XCustomMessage( + CarlaV2XCustomMessage&& x) noexcept +{ + m_header = std::move(x.m_header); + m_data = std::move(x.m_data); +} + +CarlaV2XCustomMessage& CarlaV2XCustomMessage::operator =( + const CarlaV2XCustomMessage& x) +{ + + m_header = x.m_header; + m_data = x.m_data; + return *this; +} + +CarlaV2XCustomMessage& CarlaV2XCustomMessage::operator =( + CarlaV2XCustomMessage&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_data = std::move(x.m_data); + return *this; +} + +bool CarlaV2XCustomMessage::operator ==( + const CarlaV2XCustomMessage& x) const +{ + return (m_header == x.m_header && + m_data == x.m_data); +} + +bool CarlaV2XCustomMessage::operator !=( + const CarlaV2XCustomMessage& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& 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& 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 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 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& CarlaV2XCustomMessage::data() const +{ + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +carla_msgs::msg::CarlaV2XByteArray& CarlaV2XCustomMessage::data() +{ + return m_data; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaV2XCustomMessageCdrAux.ipp" + 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..45f62093824 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessage.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "etsi_its_cam_msgs/msg/ItsPduHeader.h" +#include "CarlaV2XByteArray.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessageCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessageCdrAux.hpp new file mode 100644 index 00000000000..b69e18cba75 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessageCdrAux.hpp @@ -0,0 +1,54 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XCustomMessageCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGECDRAUX_HPP_ + +#include "CarlaV2XCustomMessage.h" + +constexpr uint32_t carla_msgs_msg_CarlaV2XCustomMessage_max_cdr_typesize {125UL}; +constexpr uint32_t carla_msgs_msg_CarlaV2XCustomMessage_max_key_cdr_typesize {0UL}; + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XCustomMessage& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessageCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessageCdrAux.ipp new file mode 100644 index 00000000000..c7d891f6c34 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessageCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XCustomMessageCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGECDRAUX_IPP_ + +#include "CarlaV2XCustomMessageCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaV2XCustomMessage& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.data(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XCustomMessage& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.data() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaV2XCustomMessage& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.data(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XCustomMessage& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGECDRAUX_IPP_ + 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..46b6fb68edb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessagePubSubTypes.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 CarlaV2XCustomMessagePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaV2XCustomMessagePubSubTypes.h" +#include "CarlaV2XCustomMessageCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaV2XCustomMessagePubSubType::CarlaV2XCustomMessagePubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaV2XCustomMessage_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaV2XCustomMessage::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaV2XCustomMessage_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaV2XCustomMessagePubSubType::~CarlaV2XCustomMessagePubSubType() +{ +} + +bool CarlaV2XCustomMessagePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaV2XCustomMessagePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaV2XCustomMessagePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..77b52d097e9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XCustomMessagePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaV2XCustomMessage.h" + +#include "etsi_its_cam_msgs/msg/ItsPduHeaderPubSubTypes.h" +#include "CarlaV2XByteArrayPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaV2XCustomMessagePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XCUSTOMMESSAGE_PUBSUBTYPES_H_ + 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..fbc86a77da7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XData.cxx @@ -0,0 +1,175 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaV2XData::CarlaV2XData() +{ +} + +CarlaV2XData::~CarlaV2XData() +{ +} + +CarlaV2XData::CarlaV2XData( + const CarlaV2XData& x) +{ + m_power = x.m_power; + m_message = x.m_message; +} + +CarlaV2XData::CarlaV2XData( + CarlaV2XData&& x) noexcept +{ + m_power = x.m_power; + m_message = std::move(x.m_message); +} + +CarlaV2XData& CarlaV2XData::operator =( + const CarlaV2XData& x) +{ + + m_power = x.m_power; + m_message = x.m_message; + return *this; +} + +CarlaV2XData& CarlaV2XData::operator =( + CarlaV2XData&& x) noexcept +{ + + m_power = x.m_power; + m_message = std::move(x.m_message); + return *this; +} + +bool CarlaV2XData::operator ==( + const CarlaV2XData& x) const +{ + return (m_power == x.m_power && + m_message == x.m_message); +} + +bool CarlaV2XData::operator !=( + const CarlaV2XData& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member power + * @param _power New value for member power + */ +void CarlaV2XData::power( + float _power) +{ + m_power = _power; +} + +/*! + * @brief This function returns the value of member power + * @return Value of member power + */ +float CarlaV2XData::power() const +{ + return m_power; +} + +/*! + * @brief This function returns a reference to member power + * @return Reference to member power + */ +float& 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 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 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& 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& CarlaV2XData::message() +{ + return m_message; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaV2XDataCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XData.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XData.h new file mode 100644 index 00000000000..7eae7d5546c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XData.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 CarlaV2XData.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "etsi_its_cam_msgs/msg/CAM.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(CARLAV2XDATA_SOURCE) +#define CARLAV2XDATA_DllAPI __declspec( dllexport ) +#else +#define CARLAV2XDATA_DllAPI __declspec( dllimport ) +#endif // CARLAV2XDATA_SOURCE +#else +#define CARLAV2XDATA_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLAV2XDATA_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure CarlaV2XData defined by the user in the IDL file. + * @ingroup CarlaV2XData + */ +class CarlaV2XData +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaV2XData(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaV2XData(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XData that will be copied. + */ + eProsima_user_DllExport CarlaV2XData( + const CarlaV2XData& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XData that will be copied. + */ + eProsima_user_DllExport CarlaV2XData( + CarlaV2XData&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XData that will be copied. + */ + eProsima_user_DllExport CarlaV2XData& operator =( + const CarlaV2XData& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XData that will be copied. + */ + eProsima_user_DllExport CarlaV2XData& operator =( + CarlaV2XData&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XData object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaV2XData& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XData object to compare. + */ + eProsima_user_DllExport bool operator !=( + 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 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 etsi_its_cam_msgs::msg::CAM& _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( + etsi_its_cam_msgs::msg::CAM&& _message); + + /*! + * @brief This function returns a constant reference to member message + * @return Constant reference to member message + */ + eProsima_user_DllExport const etsi_its_cam_msgs::msg::CAM& message() const; + + /*! + * @brief This function returns a reference to member message + * @return Reference to member message + */ + eProsima_user_DllExport etsi_its_cam_msgs::msg::CAM& message(); + +private: + + float m_power{0.0}; + etsi_its_cam_msgs::msg::CAM m_message; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataCdrAux.hpp new file mode 100644 index 00000000000..7910d091819 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataCdrAux.hpp @@ -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 CarlaV2XDataCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATACDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATACDRAUX_HPP_ + +#include "CarlaV2XData.h" + +constexpr uint32_t carla_msgs_msg_CarlaV2XData_max_cdr_typesize {12219UL}; +constexpr uint32_t carla_msgs_msg_CarlaV2XData_max_key_cdr_typesize {0UL}; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XData& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATACDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataCdrAux.ipp new file mode 100644 index 00000000000..b4ee2a6c36c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XDataCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATACDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATACDRAUX_IPP_ + +#include "CarlaV2XDataCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaV2XData& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.power(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.message(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XData& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.power() + << eprosima::fastcdr::MemberId(1) << data.message() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaV2XData& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.power(); + break; + + case 1: + dcdr >> data.message(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XData& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATACDRAUX_IPP_ + 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..99f69f6a719 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataList.cxx @@ -0,0 +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 CarlaV2XDataList.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + + + +CarlaV2XDataList::CarlaV2XDataList() +{ +} + +CarlaV2XDataList::~CarlaV2XDataList() +{ +} + +CarlaV2XDataList::CarlaV2XDataList( + const CarlaV2XDataList& x) +{ + m_data = x.m_data; +} + +CarlaV2XDataList::CarlaV2XDataList( + CarlaV2XDataList&& x) noexcept +{ + m_data = std::move(x.m_data); +} + +CarlaV2XDataList& CarlaV2XDataList::operator =( + const CarlaV2XDataList& x) +{ + + m_data = x.m_data; + return *this; +} + +CarlaV2XDataList& CarlaV2XDataList::operator =( + CarlaV2XDataList&& x) noexcept +{ + + m_data = std::move(x.m_data); + return *this; +} + +bool CarlaV2XDataList::operator ==( + const CarlaV2XDataList& x) const +{ + return (m_data == x.m_data); +} + +bool CarlaV2XDataList::operator !=( + const CarlaV2XDataList& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member data + * @param _data New value to be copied in member data + */ +void 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 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& CarlaV2XDataList::data() const +{ + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +std::vector& CarlaV2XDataList::data() +{ + return m_data; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaV2XDataListCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataList.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataList.h new file mode 100644 index 00000000000..ecb38146bd8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataList.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CarlaV2XData.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(CARLAV2XDATALIST_SOURCE) +#define CARLAV2XDATALIST_DllAPI __declspec( dllexport ) +#else +#define CARLAV2XDATALIST_DllAPI __declspec( dllimport ) +#endif // CARLAV2XDATALIST_SOURCE +#else +#define CARLAV2XDATALIST_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLAV2XDATALIST_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + + + + + +/*! + * @brief This class represents the structure CarlaV2XDataList defined by the user in the IDL file. + * @ingroup CarlaV2XDataList + */ +class CarlaV2XDataList +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaV2XDataList(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaV2XDataList(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XDataList that will be copied. + */ + eProsima_user_DllExport CarlaV2XDataList( + const CarlaV2XDataList& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaV2XDataList that will be copied. + */ + eProsima_user_DllExport CarlaV2XDataList( + CarlaV2XDataList&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XDataList that will be copied. + */ + eProsima_user_DllExport CarlaV2XDataList& operator =( + const CarlaV2XDataList& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaV2XDataList that will be copied. + */ + eProsima_user_DllExport CarlaV2XDataList& operator =( + CarlaV2XDataList&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XDataList object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaV2XDataList& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaV2XDataList object to compare. + */ + eProsima_user_DllExport bool operator !=( + 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::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(); + +private: + + std::vector m_data; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListCdrAux.hpp new file mode 100644 index 00000000000..9c55906a91f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListCdrAux.hpp @@ -0,0 +1,64 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XDataListCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALISTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALISTCDRAUX_HPP_ + +#include "CarlaV2XDataList.h" + +constexpr uint32_t carla_msgs_msg_CarlaV2XDataList_max_cdr_typesize {1222411UL}; +constexpr uint32_t carla_msgs_msg_CarlaV2XDataList_max_key_cdr_typesize {0UL}; + + + + + + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XDataList& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALISTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListCdrAux.ipp new file mode 100644 index 00000000000..e3c4bb237cd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListCdrAux.ipp @@ -0,0 +1,132 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaV2XDataListCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALISTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALISTCDRAUX_IPP_ + +#include "CarlaV2XDataListCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaV2XDataList& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.data(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XDataList& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.data() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaV2XDataList& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.data(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaV2XDataList& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALISTCDRAUX_IPP_ + 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..38eae96f550 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListPubSubTypes.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 CarlaV2XDataListPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaV2XDataListPubSubTypes.h" +#include "CarlaV2XDataListCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + + + +CarlaV2XDataListPubSubType::CarlaV2XDataListPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaV2XDataList_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaV2XDataList::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaV2XDataList_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaV2XDataListPubSubType::~CarlaV2XDataListPubSubType() +{ +} + +bool CarlaV2XDataListPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaV2XDataListPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaV2XDataListPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListPubSubTypes.h new file mode 100644 index 00000000000..69e81de7e3b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataListPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaV2XDataList.h" + +#include "CarlaV2XDataPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaV2XDataList 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 CarlaV2XDataList defined by the user in the IDL file. + * @ingroup CarlaV2XDataList + */ +class CarlaV2XDataListPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaV2XDataList type; + + eProsima_user_DllExport CarlaV2XDataListPubSubType(); + + eProsima_user_DllExport ~CarlaV2XDataListPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATALIST_PUBSUBTYPES_H_ + 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..a1dace40945 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataPubSubTypes.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 CarlaV2XDataPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaV2XDataPubSubTypes.h" +#include "CarlaV2XDataCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaV2XDataPubSubType::CarlaV2XDataPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaV2XData_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaV2XData::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaV2XData_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaV2XDataPubSubType::~CarlaV2XDataPubSubType() +{ +} + +bool CarlaV2XDataPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaV2XDataPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaV2XDataPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataPubSubTypes.h new file mode 100644 index 00000000000..d9e06a6e093 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaV2XDataPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaV2XData.h" + +#include "etsi_its_cam_msgs/msg/CAMPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaV2XData 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 CarlaV2XData defined by the user in the IDL file. + * @ingroup CarlaV2XData + */ +class CarlaV2XDataPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaV2XData type; + + eProsima_user_DllExport CarlaV2XDataPubSubType(); + + eProsima_user_DllExport ~CarlaV2XDataPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAV2XDATA_PUBSUBTYPES_H_ + 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..d44c271486b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControl.cxx @@ -0,0 +1,253 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaWalkerControl::CarlaWalkerControl() +{ +} + +CarlaWalkerControl::~CarlaWalkerControl() +{ +} + +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; +} + +CarlaWalkerControl::CarlaWalkerControl( + CarlaWalkerControl&& x) noexcept +{ + m_header = std::move(x.m_header); + m_direction = std::move(x.m_direction); + m_speed = x.m_speed; + m_jump = x.m_jump; +} + +CarlaWalkerControl& 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; +} + +CarlaWalkerControl& CarlaWalkerControl::operator =( + CarlaWalkerControl&& x) noexcept +{ + + 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 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 CarlaWalkerControl::operator !=( + const CarlaWalkerControl& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& CarlaWalkerControl::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& 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 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 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& CarlaWalkerControl::direction() const +{ + return m_direction; +} + +/*! + * @brief This function returns a reference to member direction + * @return Reference to member direction + */ +geometry_msgs::msg::Vector3& CarlaWalkerControl::direction() +{ + return m_direction; +} + + +/*! + * @brief This function sets a value in member speed + * @param _speed New value for member speed + */ +void CarlaWalkerControl::speed( + float _speed) +{ + m_speed = _speed; +} + +/*! + * @brief This function returns the value of member speed + * @return Value of member speed + */ +float CarlaWalkerControl::speed() const +{ + return m_speed; +} + +/*! + * @brief This function returns a reference to member speed + * @return Reference to member speed + */ +float& CarlaWalkerControl::speed() +{ + return m_speed; +} + + +/*! + * @brief This function sets a value in member jump + * @param _jump New value for member jump + */ +void CarlaWalkerControl::jump( + bool _jump) +{ + m_jump = _jump; +} + +/*! + * @brief This function returns the value of member jump + * @return Value of member jump + */ +bool CarlaWalkerControl::jump() const +{ + return m_jump; +} + +/*! + * @brief This function returns a reference to member jump + * @return Reference to member jump + */ +bool& CarlaWalkerControl::jump() +{ + return m_jump; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaWalkerControlCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControl.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControl.h new file mode 100644 index 00000000000..e254790aeef --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControl.h @@ -0,0 +1,248 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "geometry_msgs/msg/Vector3.h" +#include "std_msgs/msg/Header.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(CARLAWALKERCONTROL_SOURCE) +#define CARLAWALKERCONTROL_DllAPI __declspec( dllexport ) +#else +#define CARLAWALKERCONTROL_DllAPI __declspec( dllimport ) +#endif // CARLAWALKERCONTROL_SOURCE +#else +#define CARLAWALKERCONTROL_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define CARLAWALKERCONTROL_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace carla_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure CarlaWalkerControl defined by the user in the IDL file. + * @ingroup CarlaWalkerControl + */ +class CarlaWalkerControl +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport CarlaWalkerControl(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~CarlaWalkerControl(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object carla_msgs::msg::CarlaWalkerControl that will be copied. + */ + eProsima_user_DllExport CarlaWalkerControl( + const CarlaWalkerControl& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object carla_msgs::msg::CarlaWalkerControl that will be copied. + */ + eProsima_user_DllExport CarlaWalkerControl( + CarlaWalkerControl&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object carla_msgs::msg::CarlaWalkerControl that will be copied. + */ + eProsima_user_DllExport CarlaWalkerControl& operator =( + const CarlaWalkerControl& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object carla_msgs::msg::CarlaWalkerControl that will be copied. + */ + eProsima_user_DllExport CarlaWalkerControl& operator =( + CarlaWalkerControl&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaWalkerControl object to compare. + */ + eProsima_user_DllExport bool operator ==( + const CarlaWalkerControl& x) const; + + /*! + * @brief Comparison operator. + * @param x carla_msgs::msg::CarlaWalkerControl object to compare. + */ + eProsima_user_DllExport bool operator !=( + const CarlaWalkerControl& 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 direction + * @param _direction New value to be copied in member direction + */ + eProsima_user_DllExport void direction( + const geometry_msgs::msg::Vector3& _direction); + + /*! + * @brief This function moves the value in member direction + * @param _direction New value to be moved in member direction + */ + eProsima_user_DllExport void direction( + geometry_msgs::msg::Vector3&& _direction); + + /*! + * @brief This function returns a constant reference to member direction + * @return Constant reference to member direction + */ + eProsima_user_DllExport const geometry_msgs::msg::Vector3& direction() const; + + /*! + * @brief This function returns a reference to member direction + * @return Reference to member direction + */ + 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 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 jump + * @param _jump New value for member jump + */ + eProsima_user_DllExport void jump( + bool _jump); + + /*! + * @brief This function returns the value of member jump + * @return Value of member jump + */ + 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(); + +private: + + std_msgs::msg::Header m_header; + geometry_msgs::msg::Vector3 m_direction; + float m_speed{0.0}; + bool m_jump{false}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlCdrAux.hpp new file mode 100644 index 00000000000..bee8cce69f8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaWalkerControlCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROLCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROLCDRAUX_HPP_ + +#include "CarlaWalkerControl.h" + +constexpr uint32_t carla_msgs_msg_CarlaWalkerControl_max_cdr_typesize {317UL}; +constexpr uint32_t carla_msgs_msg_CarlaWalkerControl_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaWalkerControl& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROLCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlCdrAux.ipp new file mode 100644 index 00000000000..7cffeeee60d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlCdrAux.ipp @@ -0,0 +1,154 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaWalkerControlCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROLCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROLCDRAUX_IPP_ + +#include "CarlaWalkerControlCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaWalkerControl& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.direction(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.speed(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.jump(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaWalkerControl& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.direction() + << eprosima::fastcdr::MemberId(2) << data.speed() + << eprosima::fastcdr::MemberId(3) << data.jump() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaWalkerControl& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.direction(); + break; + + case 2: + dcdr >> data.speed(); + break; + + case 3: + dcdr >> data.jump(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaWalkerControl& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROLCDRAUX_IPP_ + 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..e77cbb3f7bb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlPubSubTypes.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 CarlaWalkerControlPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaWalkerControlPubSubTypes.h" +#include "CarlaWalkerControlCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaWalkerControlPubSubType::CarlaWalkerControlPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaWalkerControl_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaWalkerControl::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaWalkerControl_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaWalkerControlPubSubType::~CarlaWalkerControlPubSubType() +{ +} + +bool CarlaWalkerControlPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaWalkerControlPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaWalkerControlPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace carla_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlPubSubTypes.h new file mode 100644 index 00000000000..9089189eca9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWalkerControlPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaWalkerControl.h" + +#include "geometry_msgs/msg/Vector3PubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CarlaWalkerControl 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 CarlaWalkerControl defined by the user in the IDL file. + * @ingroup CarlaWalkerControl + */ +class CarlaWalkerControlPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CarlaWalkerControl type; + + eProsima_user_DllExport CarlaWalkerControlPubSubType(); + + eProsima_user_DllExport ~CarlaWalkerControlPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWALKERCONTROL_PUBSUBTYPES_H_ + 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..1d1b0022dc4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParameters.cxx @@ -0,0 +1,573 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaWeatherParameters::CarlaWeatherParameters() +{ +} + +CarlaWeatherParameters::~CarlaWeatherParameters() +{ +} + +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_sun_azimuth_angle = x.m_sun_azimuth_angle; + m_sun_altitude_angle = x.m_sun_altitude_angle; + m_fog_density = x.m_fog_density; + m_fog_distance = x.m_fog_distance; + m_fog_falloff = x.m_fog_falloff; + m_wetness = x.m_wetness; + m_scattering_intensity = x.m_scattering_intensity; + m_mie_scattering_scale = x.m_mie_scattering_scale; + m_rayleigh_scattering_scale = x.m_rayleigh_scattering_scale; + m_dust_storm = x.m_dust_storm; +} + +CarlaWeatherParameters::CarlaWeatherParameters( + CarlaWeatherParameters&& x) noexcept +{ + 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_sun_azimuth_angle = x.m_sun_azimuth_angle; + m_sun_altitude_angle = x.m_sun_altitude_angle; + m_fog_density = x.m_fog_density; + m_fog_distance = x.m_fog_distance; + m_fog_falloff = x.m_fog_falloff; + m_wetness = x.m_wetness; + m_scattering_intensity = x.m_scattering_intensity; + m_mie_scattering_scale = x.m_mie_scattering_scale; + m_rayleigh_scattering_scale = x.m_rayleigh_scattering_scale; + m_dust_storm = x.m_dust_storm; +} + +CarlaWeatherParameters& 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_sun_azimuth_angle = x.m_sun_azimuth_angle; + m_sun_altitude_angle = x.m_sun_altitude_angle; + m_fog_density = x.m_fog_density; + m_fog_distance = x.m_fog_distance; + m_fog_falloff = x.m_fog_falloff; + m_wetness = x.m_wetness; + m_scattering_intensity = x.m_scattering_intensity; + m_mie_scattering_scale = x.m_mie_scattering_scale; + m_rayleigh_scattering_scale = x.m_rayleigh_scattering_scale; + m_dust_storm = x.m_dust_storm; + return *this; +} + +CarlaWeatherParameters& CarlaWeatherParameters::operator =( + CarlaWeatherParameters&& x) noexcept +{ + + 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_sun_azimuth_angle = x.m_sun_azimuth_angle; + m_sun_altitude_angle = x.m_sun_altitude_angle; + m_fog_density = x.m_fog_density; + m_fog_distance = x.m_fog_distance; + m_fog_falloff = x.m_fog_falloff; + m_wetness = x.m_wetness; + m_scattering_intensity = x.m_scattering_intensity; + m_mie_scattering_scale = x.m_mie_scattering_scale; + m_rayleigh_scattering_scale = x.m_rayleigh_scattering_scale; + m_dust_storm = x.m_dust_storm; + return *this; +} + +bool 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_sun_azimuth_angle == x.m_sun_azimuth_angle && + m_sun_altitude_angle == x.m_sun_altitude_angle && + m_fog_density == x.m_fog_density && + m_fog_distance == x.m_fog_distance && + m_fog_falloff == x.m_fog_falloff && + m_wetness == x.m_wetness && + m_scattering_intensity == x.m_scattering_intensity && + m_mie_scattering_scale == x.m_mie_scattering_scale && + m_rayleigh_scattering_scale == x.m_rayleigh_scattering_scale && + m_dust_storm == x.m_dust_storm); +} + +bool CarlaWeatherParameters::operator !=( + const CarlaWeatherParameters& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member cloudiness + * @param _cloudiness New value for member cloudiness + */ +void CarlaWeatherParameters::cloudiness( + float _cloudiness) +{ + m_cloudiness = _cloudiness; +} + +/*! + * @brief This function returns the value of member cloudiness + * @return Value of member cloudiness + */ +float CarlaWeatherParameters::cloudiness() const +{ + return m_cloudiness; +} + +/*! + * @brief This function returns a reference to member cloudiness + * @return Reference to member cloudiness + */ +float& CarlaWeatherParameters::cloudiness() +{ + return m_cloudiness; +} + + +/*! + * @brief This function sets a value in member precipitation + * @param _precipitation New value for member precipitation + */ +void CarlaWeatherParameters::precipitation( + float _precipitation) +{ + m_precipitation = _precipitation; +} + +/*! + * @brief This function returns the value of member precipitation + * @return Value of member precipitation + */ +float CarlaWeatherParameters::precipitation() const +{ + return m_precipitation; +} + +/*! + * @brief This function returns a reference to member precipitation + * @return Reference to member precipitation + */ +float& 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 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 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& 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 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 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& CarlaWeatherParameters::wind_intensity() +{ + return m_wind_intensity; +} + + +/*! + * @brief This function sets a value in member sun_azimuth_angle + * @param _sun_azimuth_angle New value for member sun_azimuth_angle + */ +void 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 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& 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 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 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& CarlaWeatherParameters::sun_altitude_angle() +{ + return m_sun_altitude_angle; +} + + +/*! + * @brief This function sets a value in member fog_density + * @param _fog_density New value for member fog_density + */ +void 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 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& 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 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 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& CarlaWeatherParameters::fog_distance() +{ + return m_fog_distance; +} + + +/*! + * @brief This function sets a value in member fog_falloff + * @param _fog_falloff New value for member fog_falloff + */ +void CarlaWeatherParameters::fog_falloff( + float _fog_falloff) +{ + m_fog_falloff = _fog_falloff; +} + +/*! + * @brief This function returns the value of member fog_falloff + * @return Value of member fog_falloff + */ +float CarlaWeatherParameters::fog_falloff() const +{ + return m_fog_falloff; +} + +/*! + * @brief This function returns a reference to member fog_falloff + * @return Reference to member fog_falloff + */ +float& CarlaWeatherParameters::fog_falloff() +{ + return m_fog_falloff; +} + + +/*! + * @brief This function sets a value in member wetness + * @param _wetness New value for member wetness + */ +void CarlaWeatherParameters::wetness( + float _wetness) +{ + m_wetness = _wetness; +} + +/*! + * @brief This function returns the value of member wetness + * @return Value of member wetness + */ +float CarlaWeatherParameters::wetness() const +{ + return m_wetness; +} + +/*! + * @brief This function returns a reference to member wetness + * @return Reference to member wetness + */ +float& CarlaWeatherParameters::wetness() +{ + return m_wetness; +} + + +/*! + * @brief This function sets a value in member scattering_intensity + * @param _scattering_intensity New value for member scattering_intensity + */ +void CarlaWeatherParameters::scattering_intensity( + float _scattering_intensity) +{ + m_scattering_intensity = _scattering_intensity; +} + +/*! + * @brief This function returns the value of member scattering_intensity + * @return Value of member scattering_intensity + */ +float CarlaWeatherParameters::scattering_intensity() const +{ + return m_scattering_intensity; +} + +/*! + * @brief This function returns a reference to member scattering_intensity + * @return Reference to member scattering_intensity + */ +float& CarlaWeatherParameters::scattering_intensity() +{ + return m_scattering_intensity; +} + + +/*! + * @brief This function sets a value in member mie_scattering_scale + * @param _mie_scattering_scale New value for member mie_scattering_scale + */ +void CarlaWeatherParameters::mie_scattering_scale( + float _mie_scattering_scale) +{ + m_mie_scattering_scale = _mie_scattering_scale; +} + +/*! + * @brief This function returns the value of member mie_scattering_scale + * @return Value of member mie_scattering_scale + */ +float CarlaWeatherParameters::mie_scattering_scale() const +{ + return m_mie_scattering_scale; +} + +/*! + * @brief This function returns a reference to member mie_scattering_scale + * @return Reference to member mie_scattering_scale + */ +float& CarlaWeatherParameters::mie_scattering_scale() +{ + return m_mie_scattering_scale; +} + + +/*! + * @brief This function sets a value in member rayleigh_scattering_scale + * @param _rayleigh_scattering_scale New value for member rayleigh_scattering_scale + */ +void CarlaWeatherParameters::rayleigh_scattering_scale( + float _rayleigh_scattering_scale) +{ + m_rayleigh_scattering_scale = _rayleigh_scattering_scale; +} + +/*! + * @brief This function returns the value of member rayleigh_scattering_scale + * @return Value of member rayleigh_scattering_scale + */ +float CarlaWeatherParameters::rayleigh_scattering_scale() const +{ + return m_rayleigh_scattering_scale; +} + +/*! + * @brief This function returns a reference to member rayleigh_scattering_scale + * @return Reference to member rayleigh_scattering_scale + */ +float& CarlaWeatherParameters::rayleigh_scattering_scale() +{ + return m_rayleigh_scattering_scale; +} + + +/*! + * @brief This function sets a value in member dust_storm + * @param _dust_storm New value for member dust_storm + */ +void CarlaWeatherParameters::dust_storm( + float _dust_storm) +{ + m_dust_storm = _dust_storm; +} + +/*! + * @brief This function returns the value of member dust_storm + * @return Value of member dust_storm + */ +float CarlaWeatherParameters::dust_storm() const +{ + return m_dust_storm; +} + +/*! + * @brief This function returns a reference to member dust_storm + * @return Reference to member dust_storm + */ +float& CarlaWeatherParameters::dust_storm() +{ + return m_dust_storm; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaWeatherParametersCdrAux.ipp" + 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..0e09ed8e343 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParameters.h @@ -0,0 +1,442 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_H_ + +#include +#include +#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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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 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 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 fog_falloff + * @param _fog_falloff New value for member fog_falloff + */ + eProsima_user_DllExport void fog_falloff( + float _fog_falloff); + + /*! + * @brief This function returns the value of member fog_falloff + * @return Value of member fog_falloff + */ + eProsima_user_DllExport float fog_falloff() const; + + /*! + * @brief This function returns a reference to member fog_falloff + * @return Reference to member fog_falloff + */ + eProsima_user_DllExport float& fog_falloff(); + + + /*! + * @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 scattering_intensity + * @param _scattering_intensity New value for member scattering_intensity + */ + eProsima_user_DllExport void scattering_intensity( + float _scattering_intensity); + + /*! + * @brief This function returns the value of member scattering_intensity + * @return Value of member scattering_intensity + */ + eProsima_user_DllExport float scattering_intensity() const; + + /*! + * @brief This function returns a reference to member scattering_intensity + * @return Reference to member scattering_intensity + */ + eProsima_user_DllExport float& scattering_intensity(); + + + /*! + * @brief This function sets a value in member mie_scattering_scale + * @param _mie_scattering_scale New value for member mie_scattering_scale + */ + eProsima_user_DllExport void mie_scattering_scale( + float _mie_scattering_scale); + + /*! + * @brief This function returns the value of member mie_scattering_scale + * @return Value of member mie_scattering_scale + */ + eProsima_user_DllExport float mie_scattering_scale() const; + + /*! + * @brief This function returns a reference to member mie_scattering_scale + * @return Reference to member mie_scattering_scale + */ + eProsima_user_DllExport float& mie_scattering_scale(); + + + /*! + * @brief This function sets a value in member rayleigh_scattering_scale + * @param _rayleigh_scattering_scale New value for member rayleigh_scattering_scale + */ + eProsima_user_DllExport void rayleigh_scattering_scale( + float _rayleigh_scattering_scale); + + /*! + * @brief This function returns the value of member rayleigh_scattering_scale + * @return Value of member rayleigh_scattering_scale + */ + eProsima_user_DllExport float rayleigh_scattering_scale() const; + + /*! + * @brief This function returns a reference to member rayleigh_scattering_scale + * @return Reference to member rayleigh_scattering_scale + */ + eProsima_user_DllExport float& rayleigh_scattering_scale(); + + + /*! + * @brief This function sets a value in member dust_storm + * @param _dust_storm New value for member dust_storm + */ + eProsima_user_DllExport void dust_storm( + float _dust_storm); + + /*! + * @brief This function returns the value of member dust_storm + * @return Value of member dust_storm + */ + eProsima_user_DllExport float dust_storm() const; + + /*! + * @brief This function returns a reference to member dust_storm + * @return Reference to member dust_storm + */ + eProsima_user_DllExport float& dust_storm(); + +private: + + float m_cloudiness{0.0}; + float m_precipitation{0.0}; + float m_precipitation_deposits{0.0}; + float m_wind_intensity{0.0}; + float m_sun_azimuth_angle{0.0}; + float m_sun_altitude_angle{0.0}; + float m_fog_density{0.0}; + float m_fog_distance{0.0}; + float m_fog_falloff{0.0}; + float m_wetness{0.0}; + float m_scattering_intensity{0.0}; + float m_mie_scattering_scale{0.0}; + float m_rayleigh_scattering_scale{0.0331}; + float m_dust_storm{0.0}; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersCdrAux.hpp new file mode 100644 index 00000000000..a191ff15c62 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaWeatherParametersCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERSCDRAUX_HPP_ + +#include "CarlaWeatherParameters.h" + +constexpr uint32_t carla_msgs_msg_CarlaWeatherParameters_max_cdr_typesize {60UL}; +constexpr uint32_t carla_msgs_msg_CarlaWeatherParameters_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaWeatherParameters& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersCdrAux.ipp new file mode 100644 index 00000000000..e5807082ee4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersCdrAux.ipp @@ -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 CarlaWeatherParametersCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERSCDRAUX_IPP_ + +#include "CarlaWeatherParametersCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaWeatherParameters& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.cloudiness(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.precipitation(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.precipitation_deposits(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.wind_intensity(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.sun_azimuth_angle(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.sun_altitude_angle(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.fog_density(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.fog_distance(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.fog_falloff(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), + data.wetness(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(10), + data.scattering_intensity(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(11), + data.mie_scattering_scale(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(12), + data.rayleigh_scattering_scale(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(13), + data.dust_storm(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaWeatherParameters& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.cloudiness() + << eprosima::fastcdr::MemberId(1) << data.precipitation() + << eprosima::fastcdr::MemberId(2) << data.precipitation_deposits() + << eprosima::fastcdr::MemberId(3) << data.wind_intensity() + << eprosima::fastcdr::MemberId(4) << data.sun_azimuth_angle() + << eprosima::fastcdr::MemberId(5) << data.sun_altitude_angle() + << eprosima::fastcdr::MemberId(6) << data.fog_density() + << eprosima::fastcdr::MemberId(7) << data.fog_distance() + << eprosima::fastcdr::MemberId(8) << data.fog_falloff() + << eprosima::fastcdr::MemberId(9) << data.wetness() + << eprosima::fastcdr::MemberId(10) << data.scattering_intensity() + << eprosima::fastcdr::MemberId(11) << data.mie_scattering_scale() + << eprosima::fastcdr::MemberId(12) << data.rayleigh_scattering_scale() + << eprosima::fastcdr::MemberId(13) << data.dust_storm() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaWeatherParameters& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.cloudiness(); + break; + + case 1: + dcdr >> data.precipitation(); + break; + + case 2: + dcdr >> data.precipitation_deposits(); + break; + + case 3: + dcdr >> data.wind_intensity(); + break; + + case 4: + dcdr >> data.sun_azimuth_angle(); + break; + + case 5: + dcdr >> data.sun_altitude_angle(); + break; + + case 6: + dcdr >> data.fog_density(); + break; + + case 7: + dcdr >> data.fog_distance(); + break; + + case 8: + dcdr >> data.fog_falloff(); + break; + + case 9: + dcdr >> data.wetness(); + break; + + case 10: + dcdr >> data.scattering_intensity(); + break; + + case 11: + dcdr >> data.mie_scattering_scale(); + break; + + case 12: + dcdr >> data.rayleigh_scattering_scale(); + break; + + case 13: + dcdr >> data.dust_storm(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaWeatherParameters& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERSCDRAUX_IPP_ + 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..d0242058cda --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersPubSubTypes.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 CarlaWeatherParametersPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaWeatherParametersPubSubTypes.h" +#include "CarlaWeatherParametersCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaWeatherParametersPubSubType::CarlaWeatherParametersPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaWeatherParameters_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaWeatherParameters::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaWeatherParameters_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaWeatherParametersPubSubType::~CarlaWeatherParametersPubSubType() +{ +} + +bool CarlaWeatherParametersPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaWeatherParametersPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaWeatherParametersPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..3e85a27b640 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWeatherParametersPubSubTypes.h @@ -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 CarlaWeatherParametersPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaWeatherParameters.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaWeatherParametersPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWEATHERPARAMETERS_PUBSUBTYPES_H_ + 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..cb845866356 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfo.cxx @@ -0,0 +1,229 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace msg { + + + +CarlaWorldInfo::CarlaWorldInfo() +{ +} + +CarlaWorldInfo::~CarlaWorldInfo() +{ +} + +CarlaWorldInfo::CarlaWorldInfo( + const CarlaWorldInfo& x) +{ + m_carla_version = x.m_carla_version; + m_map_name = x.m_map_name; + m_opendrive = x.m_opendrive; +} + +CarlaWorldInfo::CarlaWorldInfo( + CarlaWorldInfo&& x) noexcept +{ + m_carla_version = std::move(x.m_carla_version); + m_map_name = std::move(x.m_map_name); + m_opendrive = std::move(x.m_opendrive); +} + +CarlaWorldInfo& CarlaWorldInfo::operator =( + const CarlaWorldInfo& x) +{ + + m_carla_version = x.m_carla_version; + m_map_name = x.m_map_name; + m_opendrive = x.m_opendrive; + return *this; +} + +CarlaWorldInfo& CarlaWorldInfo::operator =( + CarlaWorldInfo&& x) noexcept +{ + + m_carla_version = std::move(x.m_carla_version); + m_map_name = std::move(x.m_map_name); + m_opendrive = std::move(x.m_opendrive); + return *this; +} + +bool CarlaWorldInfo::operator ==( + const CarlaWorldInfo& x) const +{ + return (m_carla_version == x.m_carla_version && + m_map_name == x.m_map_name && + m_opendrive == x.m_opendrive); +} + +bool CarlaWorldInfo::operator !=( + const CarlaWorldInfo& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member carla_version + * @param _carla_version New value to be copied in member carla_version + */ +void CarlaWorldInfo::carla_version( + const std::string& _carla_version) +{ + m_carla_version = _carla_version; +} + +/*! + * @brief This function moves the value in member carla_version + * @param _carla_version New value to be moved in member carla_version + */ +void CarlaWorldInfo::carla_version( + std::string&& _carla_version) +{ + m_carla_version = std::move(_carla_version); +} + +/*! + * @brief This function returns a constant reference to member carla_version + * @return Constant reference to member carla_version + */ +const std::string& CarlaWorldInfo::carla_version() const +{ + return m_carla_version; +} + +/*! + * @brief This function returns a reference to member carla_version + * @return Reference to member carla_version + */ +std::string& CarlaWorldInfo::carla_version() +{ + return m_carla_version; +} + + +/*! + * @brief This function copies the value in member map_name + * @param _map_name New value to be copied in member map_name + */ +void 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 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& 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& 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 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 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& CarlaWorldInfo::opendrive() const +{ + return m_opendrive; +} + +/*! + * @brief This function returns a reference to member opendrive + * @return Reference to member opendrive + */ +std::string& CarlaWorldInfo::opendrive() +{ + return m_opendrive; +} + + + + +} // namespace msg + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CarlaWorldInfoCdrAux.ipp" + 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..f5b29f1fdb8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfo.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 CarlaWorldInfo.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_H_ + +#include +#include +#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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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 carla_version + * @param _carla_version New value to be copied in member carla_version + */ + eProsima_user_DllExport void carla_version( + const std::string& _carla_version); + + /*! + * @brief This function moves the value in member carla_version + * @param _carla_version New value to be moved in member carla_version + */ + eProsima_user_DllExport void carla_version( + std::string&& _carla_version); + + /*! + * @brief This function returns a constant reference to member carla_version + * @return Constant reference to member carla_version + */ + eProsima_user_DllExport const std::string& carla_version() const; + + /*! + * @brief This function returns a reference to member carla_version + * @return Reference to member carla_version + */ + eProsima_user_DllExport std::string& carla_version(); + + + /*! + * @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(); + +private: + + std::string m_carla_version; + std::string m_map_name; + std::string m_opendrive; + +}; + +} // namespace msg + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoCdrAux.hpp new file mode 100644 index 00000000000..d100bc283f5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaWorldInfoCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFOCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFOCDRAUX_HPP_ + +#include "CarlaWorldInfo.h" + +constexpr uint32_t carla_msgs_msg_CarlaWorldInfo_max_cdr_typesize {784UL}; +constexpr uint32_t carla_msgs_msg_CarlaWorldInfo_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaWorldInfo& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFOCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoCdrAux.ipp new file mode 100644 index 00000000000..cdd0d2b7b4a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CarlaWorldInfoCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFOCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFOCDRAUX_IPP_ + +#include "CarlaWorldInfoCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::msg::CarlaWorldInfo& data, + size_t& current_alignment) +{ + using namespace carla_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.carla_version(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.map_name(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.opendrive(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaWorldInfo& data) +{ + using namespace carla_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.carla_version() + << eprosima::fastcdr::MemberId(1) << data.map_name() + << eprosima::fastcdr::MemberId(2) << data.opendrive() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::msg::CarlaWorldInfo& data) +{ + using namespace carla_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.carla_version(); + break; + + case 1: + dcdr >> data.map_name(); + break; + + case 2: + dcdr >> data.opendrive(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::msg::CarlaWorldInfo& data) +{ + using namespace carla_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFOCDRAUX_IPP_ + 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..d7a5abcd5a4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoPubSubTypes.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 CarlaWorldInfoPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CarlaWorldInfoPubSubTypes.h" +#include "CarlaWorldInfoCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace msg { + + +CarlaWorldInfoPubSubType::CarlaWorldInfoPubSubType() +{ + setName("carla_msgs::msg::dds_::CarlaWorldInfo_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CarlaWorldInfo::getMaxCdrSerializedSize()); +#else + carla_msgs_msg_CarlaWorldInfo_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CarlaWorldInfoPubSubType::~CarlaWorldInfoPubSubType() +{ +} + +bool CarlaWorldInfoPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CarlaWorldInfoPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CarlaWorldInfoPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..9e411a456f0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/msg/CarlaWorldInfoPubSubTypes.h @@ -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 CarlaWorldInfoPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CarlaWorldInfo.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CarlaWorldInfoPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAWORLDINFO_PUBSUBTYPES_H_ + 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..142a0e7218b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObject.cxx @@ -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 DestroyObject.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace srv { + + + +DestroyObject_Request::DestroyObject_Request() +{ +} + +DestroyObject_Request::~DestroyObject_Request() +{ +} + +DestroyObject_Request::DestroyObject_Request( + const DestroyObject_Request& x) +{ + m_id = x.m_id; +} + +DestroyObject_Request::DestroyObject_Request( + DestroyObject_Request&& x) noexcept +{ + m_id = x.m_id; +} + +DestroyObject_Request& DestroyObject_Request::operator =( + const DestroyObject_Request& x) +{ + + m_id = x.m_id; + return *this; +} + +DestroyObject_Request& DestroyObject_Request::operator =( + DestroyObject_Request&& x) noexcept +{ + + m_id = x.m_id; + return *this; +} + +bool DestroyObject_Request::operator ==( + const DestroyObject_Request& x) const +{ + return (m_id == x.m_id); +} + +bool DestroyObject_Request::operator !=( + const DestroyObject_Request& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void 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 DestroyObject_Request::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +int32_t& DestroyObject_Request::id() +{ + return m_id; +} + + + + +DestroyObject_Response::DestroyObject_Response() +{ +} + +DestroyObject_Response::~DestroyObject_Response() +{ +} + +DestroyObject_Response::DestroyObject_Response( + const DestroyObject_Response& x) +{ + m_success = x.m_success; +} + +DestroyObject_Response::DestroyObject_Response( + DestroyObject_Response&& x) noexcept +{ + m_success = x.m_success; +} + +DestroyObject_Response& DestroyObject_Response::operator =( + const DestroyObject_Response& x) +{ + + m_success = x.m_success; + return *this; +} + +DestroyObject_Response& DestroyObject_Response::operator =( + DestroyObject_Response&& x) noexcept +{ + + m_success = x.m_success; + return *this; +} + +bool DestroyObject_Response::operator ==( + const DestroyObject_Response& x) const +{ + return (m_success == x.m_success); +} + +bool DestroyObject_Response::operator !=( + const DestroyObject_Response& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member success + * @param _success New value for member success + */ +void DestroyObject_Response::success( + bool _success) +{ + m_success = _success; +} + +/*! + * @brief This function returns the value of member success + * @return Value of member success + */ +bool DestroyObject_Response::success() const +{ + return m_success; +} + +/*! + * @brief This function returns a reference to member success + * @return Reference to member success + */ +bool& DestroyObject_Response::success() +{ + return m_success; +} + + + + +} // namespace srv + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "DestroyObjectCdrAux.ipp" + 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..290ece54122 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObject.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 DestroyObject.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_H_ + +#include +#include +#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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int32_t m_id{0}; + +}; + + +/*! + * @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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + bool m_success{false}; + +}; + +} // namespace srv + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectCdrAux.hpp new file mode 100644 index 00000000000..11b9f35ff91 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectCdrAux.hpp @@ -0,0 +1,59 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DestroyObjectCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECTCDRAUX_HPP_ + +#include "DestroyObject.h" + +constexpr uint32_t carla_msgs_srv_DestroyObject_Request_max_cdr_typesize {8UL}; +constexpr uint32_t carla_msgs_srv_DestroyObject_Request_max_key_cdr_typesize {0UL}; + +constexpr uint32_t carla_msgs_srv_DestroyObject_Response_max_cdr_typesize {5UL}; +constexpr uint32_t carla_msgs_srv_DestroyObject_Response_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::DestroyObject_Request& data); + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::DestroyObject_Response& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectCdrAux.ipp new file mode 100644 index 00000000000..719e8389fd8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectCdrAux.ipp @@ -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 DestroyObjectCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECTCDRAUX_IPP_ + +#include "DestroyObjectCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::DestroyObject_Request& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.id(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::DestroyObject_Request& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.id() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::DestroyObject_Request& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.id(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::DestroyObject_Request& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::DestroyObject_Response& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.success(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::DestroyObject_Response& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.success() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::DestroyObject_Response& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.success(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::DestroyObject_Response& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECTCDRAUX_IPP_ + 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..2e0a4ae892b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectPubSubTypes.cxx @@ -0,0 +1,354 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "DestroyObjectPubSubTypes.h" +#include "DestroyObjectCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace srv { + + +DestroyObject_RequestPubSubType::DestroyObject_RequestPubSubType() +{ + setName("carla_msgs::srv::dds_::DestroyObject_Request_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DestroyObject_Request::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_DestroyObject_Request_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +DestroyObject_RequestPubSubType::~DestroyObject_RequestPubSubType() +{ +} + +bool DestroyObject_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool DestroyObject_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function DestroyObject_RequestPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + + +DestroyObject_ResponsePubSubType::DestroyObject_ResponsePubSubType() +{ + setName("carla_msgs::srv::dds_::DestroyObject_Response_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DestroyObject_Response::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_DestroyObject_Response_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +DestroyObject_ResponsePubSubType::~DestroyObject_ResponsePubSubType() +{ +} + +bool DestroyObject_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool DestroyObject_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function DestroyObject_ResponsePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..ec7a8d06b49 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/DestroyObjectPubSubTypes.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 DestroyObjectPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "DestroyObject.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~DestroyObject_RequestPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; + + + +/*! + * @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 ~DestroyObject_ResponsePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_DESTROYOBJECT_PUBSUBTYPES_H_ + 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..92b3ce682f6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMaps.cxx @@ -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 GetAvailableMaps.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace srv { + + + +GetAvailableMaps_Request::GetAvailableMaps_Request() +{ +} + +GetAvailableMaps_Request::~GetAvailableMaps_Request() +{ +} + +GetAvailableMaps_Request::GetAvailableMaps_Request( + const GetAvailableMaps_Request& x) +{ + m_structure_needs_at_least_one_member = x.m_structure_needs_at_least_one_member; +} + +GetAvailableMaps_Request::GetAvailableMaps_Request( + GetAvailableMaps_Request&& x) noexcept +{ + m_structure_needs_at_least_one_member = x.m_structure_needs_at_least_one_member; +} + +GetAvailableMaps_Request& GetAvailableMaps_Request::operator =( + const GetAvailableMaps_Request& x) +{ + + m_structure_needs_at_least_one_member = x.m_structure_needs_at_least_one_member; + return *this; +} + +GetAvailableMaps_Request& GetAvailableMaps_Request::operator =( + GetAvailableMaps_Request&& x) noexcept +{ + + m_structure_needs_at_least_one_member = x.m_structure_needs_at_least_one_member; + return *this; +} + +bool 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 GetAvailableMaps_Request::operator !=( + const GetAvailableMaps_Request& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& GetAvailableMaps_Request::structure_needs_at_least_one_member() +{ + return m_structure_needs_at_least_one_member; +} + + + + + + +GetAvailableMaps_Response::GetAvailableMaps_Response() +{ +} + +GetAvailableMaps_Response::~GetAvailableMaps_Response() +{ +} + +GetAvailableMaps_Response::GetAvailableMaps_Response( + const GetAvailableMaps_Response& x) +{ + m_maps = x.m_maps; +} + +GetAvailableMaps_Response::GetAvailableMaps_Response( + GetAvailableMaps_Response&& x) noexcept +{ + m_maps = std::move(x.m_maps); +} + +GetAvailableMaps_Response& GetAvailableMaps_Response::operator =( + const GetAvailableMaps_Response& x) +{ + + m_maps = x.m_maps; + return *this; +} + +GetAvailableMaps_Response& GetAvailableMaps_Response::operator =( + GetAvailableMaps_Response&& x) noexcept +{ + + m_maps = std::move(x.m_maps); + return *this; +} + +bool GetAvailableMaps_Response::operator ==( + const GetAvailableMaps_Response& x) const +{ + return (m_maps == x.m_maps); +} + +bool GetAvailableMaps_Response::operator !=( + const GetAvailableMaps_Response& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member maps + * @param _maps New value to be copied in member maps + */ +void 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 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& GetAvailableMaps_Response::maps() const +{ + return m_maps; +} + +/*! + * @brief This function returns a reference to member maps + * @return Reference to member maps + */ +std::vector& GetAvailableMaps_Response::maps() +{ + return m_maps; +} + + + + +} // namespace srv + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "GetAvailableMapsCdrAux.ipp" + 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..ebff2b05aa5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMaps.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 GetAvailableMaps.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_H_ + +#include +#include +#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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_structure_needs_at_least_one_member{0}; + +}; + + + + +/*! + * @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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_maps; + +}; + +} // namespace srv + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsCdrAux.hpp new file mode 100644 index 00000000000..a43330ce08b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file GetAvailableMapsCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPSCDRAUX_HPP_ + +#include "GetAvailableMaps.h" + +constexpr uint32_t carla_msgs_srv_GetAvailableMaps_Response_max_cdr_typesize {26012UL}; +constexpr uint32_t carla_msgs_srv_GetAvailableMaps_Response_max_key_cdr_typesize {0UL}; + +constexpr uint32_t carla_msgs_srv_GetAvailableMaps_Request_max_cdr_typesize {5UL}; +constexpr uint32_t carla_msgs_srv_GetAvailableMaps_Request_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetAvailableMaps_Request& data); + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetAvailableMaps_Response& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsCdrAux.ipp new file mode 100644 index 00000000000..30dbfe2cbd1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsCdrAux.ipp @@ -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 GetAvailableMapsCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPSCDRAUX_IPP_ + +#include "GetAvailableMapsCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::GetAvailableMaps_Request& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.structure_needs_at_least_one_member(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetAvailableMaps_Request& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.structure_needs_at_least_one_member() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::GetAvailableMaps_Request& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.structure_needs_at_least_one_member(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetAvailableMaps_Request& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::GetAvailableMaps_Response& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.maps(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetAvailableMaps_Response& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.maps() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::GetAvailableMaps_Response& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.maps(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetAvailableMaps_Response& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPSCDRAUX_IPP_ + 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..1f133d1745a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsPubSubTypes.cxx @@ -0,0 +1,356 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "GetAvailableMapsPubSubTypes.h" +#include "GetAvailableMapsCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace srv { + + +GetAvailableMaps_RequestPubSubType::GetAvailableMaps_RequestPubSubType() +{ + setName("carla_msgs::srv::dds_::GetAvailableMaps_Request_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(GetAvailableMaps_Request::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_GetAvailableMaps_Request_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +GetAvailableMaps_RequestPubSubType::~GetAvailableMaps_RequestPubSubType() +{ +} + +bool GetAvailableMaps_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool GetAvailableMaps_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function GetAvailableMaps_RequestPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + + + + +GetAvailableMaps_ResponsePubSubType::GetAvailableMaps_ResponsePubSubType() +{ + setName("carla_msgs::srv::dds_::GetAvailableMaps_Response_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(GetAvailableMaps_Response::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_GetAvailableMaps_Response_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +GetAvailableMaps_ResponsePubSubType::~GetAvailableMaps_ResponsePubSubType() +{ +} + +bool GetAvailableMaps_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool GetAvailableMaps_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function GetAvailableMaps_ResponsePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..924d392bae3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetAvailableMapsPubSubTypes.h @@ -0,0 +1,224 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "GetAvailableMaps.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~GetAvailableMaps_RequestPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; + + + + + +/*! + * @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 ~GetAvailableMaps_ResponsePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETAVAILABLEMAPS_PUBSUBTYPES_H_ + 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..b8e40530f49 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprints.cxx @@ -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 GetBlueprints.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace srv { + + + +GetBlueprints_Request::GetBlueprints_Request() +{ +} + +GetBlueprints_Request::~GetBlueprints_Request() +{ +} + +GetBlueprints_Request::GetBlueprints_Request( + const GetBlueprints_Request& x) +{ + m_filter = x.m_filter; +} + +GetBlueprints_Request::GetBlueprints_Request( + GetBlueprints_Request&& x) noexcept +{ + m_filter = std::move(x.m_filter); +} + +GetBlueprints_Request& GetBlueprints_Request::operator =( + const GetBlueprints_Request& x) +{ + + m_filter = x.m_filter; + return *this; +} + +GetBlueprints_Request& GetBlueprints_Request::operator =( + GetBlueprints_Request&& x) noexcept +{ + + m_filter = std::move(x.m_filter); + return *this; +} + +bool GetBlueprints_Request::operator ==( + const GetBlueprints_Request& x) const +{ + return (m_filter == x.m_filter); +} + +bool GetBlueprints_Request::operator !=( + const GetBlueprints_Request& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member filter + * @param _filter New value to be copied in member filter + */ +void 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 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& GetBlueprints_Request::filter() const +{ + return m_filter; +} + +/*! + * @brief This function returns a reference to member filter + * @return Reference to member filter + */ +std::string& GetBlueprints_Request::filter() +{ + return m_filter; +} + + + + + + +GetBlueprints_Response::GetBlueprints_Response() +{ +} + +GetBlueprints_Response::~GetBlueprints_Response() +{ +} + +GetBlueprints_Response::GetBlueprints_Response( + const GetBlueprints_Response& x) +{ + m_blueprints = x.m_blueprints; +} + +GetBlueprints_Response::GetBlueprints_Response( + GetBlueprints_Response&& x) noexcept +{ + m_blueprints = std::move(x.m_blueprints); +} + +GetBlueprints_Response& GetBlueprints_Response::operator =( + const GetBlueprints_Response& x) +{ + + m_blueprints = x.m_blueprints; + return *this; +} + +GetBlueprints_Response& GetBlueprints_Response::operator =( + GetBlueprints_Response&& x) noexcept +{ + + m_blueprints = std::move(x.m_blueprints); + return *this; +} + +bool GetBlueprints_Response::operator ==( + const GetBlueprints_Response& x) const +{ + return (m_blueprints == x.m_blueprints); +} + +bool GetBlueprints_Response::operator !=( + const GetBlueprints_Response& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member blueprints + * @param _blueprints New value to be copied in member blueprints + */ +void 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 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& GetBlueprints_Response::blueprints() const +{ + return m_blueprints; +} + +/*! + * @brief This function returns a reference to member blueprints + * @return Reference to member blueprints + */ +std::vector& GetBlueprints_Response::blueprints() +{ + return m_blueprints; +} + + + + +} // namespace srv + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "GetBlueprintsCdrAux.ipp" + 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..2084f75f48e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprints.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 GetBlueprints.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "carla_msgs/msg/CarlaActorBlueprint.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_blueprints; + +}; + +} // namespace srv + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsCdrAux.hpp new file mode 100644 index 00000000000..a3d52629c30 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsCdrAux.hpp @@ -0,0 +1,63 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file GetBlueprintsCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTSCDRAUX_HPP_ + +#include "GetBlueprints.h" + +constexpr uint32_t carla_msgs_srv_GetBlueprints_Response_max_cdr_typesize {7868012UL}; +constexpr uint32_t carla_msgs_srv_GetBlueprints_Response_max_key_cdr_typesize {0UL}; + + + +constexpr uint32_t carla_msgs_srv_GetBlueprints_Request_max_cdr_typesize {264UL}; +constexpr uint32_t carla_msgs_srv_GetBlueprints_Request_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetBlueprints_Request& data); + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetBlueprints_Response& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsCdrAux.ipp new file mode 100644 index 00000000000..453bc1298e0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsCdrAux.ipp @@ -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 GetBlueprintsCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTSCDRAUX_IPP_ + +#include "GetBlueprintsCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::GetBlueprints_Request& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.filter(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetBlueprints_Request& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.filter() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::GetBlueprints_Request& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.filter(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetBlueprints_Request& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::GetBlueprints_Response& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.blueprints(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetBlueprints_Response& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.blueprints() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::GetBlueprints_Response& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.blueprints(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::GetBlueprints_Response& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTSCDRAUX_IPP_ + 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..b7ba162d329 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsPubSubTypes.cxx @@ -0,0 +1,356 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "GetBlueprintsPubSubTypes.h" +#include "GetBlueprintsCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace srv { + + +GetBlueprints_RequestPubSubType::GetBlueprints_RequestPubSubType() +{ + setName("carla_msgs::srv::dds_::GetBlueprints_Request_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(GetBlueprints_Request::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_GetBlueprints_Request_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +GetBlueprints_RequestPubSubType::~GetBlueprints_RequestPubSubType() +{ +} + +bool GetBlueprints_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool GetBlueprints_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function GetBlueprints_RequestPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + + + + +GetBlueprints_ResponsePubSubType::GetBlueprints_ResponsePubSubType() +{ + setName("carla_msgs::srv::dds_::GetBlueprints_Response_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(GetBlueprints_Response::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_GetBlueprints_Response_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +GetBlueprints_ResponsePubSubType::~GetBlueprints_ResponsePubSubType() +{ +} + +bool GetBlueprints_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool GetBlueprints_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function GetBlueprints_ResponsePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..e7f947565e2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/GetBlueprintsPubSubTypes.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 GetBlueprintsPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "GetBlueprints.h" + +#include "carla_msgs/msg/CarlaActorBlueprintPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~GetBlueprints_RequestPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; + + + + + +/*! + * @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 ~GetBlueprints_ResponsePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_GETBLUEPRINTS_PUBSUBTYPES_H_ + 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..aa9a8667a02 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMap.cxx @@ -0,0 +1,326 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace srv { + +namespace LoadMap_Request_Constants { + + +} // namespace LoadMap_Request_Constants + + +LoadMap_Request::LoadMap_Request() +{ +} + +LoadMap_Request::~LoadMap_Request() +{ +} + +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; +} + +LoadMap_Request::LoadMap_Request( + LoadMap_Request&& x) noexcept +{ + 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; +} + +LoadMap_Request& 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; +} + +LoadMap_Request& LoadMap_Request::operator =( + LoadMap_Request&& x) noexcept +{ + + 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 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 LoadMap_Request::operator !=( + const LoadMap_Request& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member mapname + * @param _mapname New value to be copied in member mapname + */ +void 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 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& LoadMap_Request::mapname() const +{ + return m_mapname; +} + +/*! + * @brief This function returns a reference to member mapname + * @return Reference to member mapname + */ +std::string& 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 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 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& 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 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 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& 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 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 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& LoadMap_Request::map_layers() +{ + return m_map_layers; +} + + + + +LoadMap_Response::LoadMap_Response() +{ +} + +LoadMap_Response::~LoadMap_Response() +{ +} + +LoadMap_Response::LoadMap_Response( + const LoadMap_Response& x) +{ + m_success = x.m_success; +} + +LoadMap_Response::LoadMap_Response( + LoadMap_Response&& x) noexcept +{ + m_success = x.m_success; +} + +LoadMap_Response& LoadMap_Response::operator =( + const LoadMap_Response& x) +{ + + m_success = x.m_success; + return *this; +} + +LoadMap_Response& LoadMap_Response::operator =( + LoadMap_Response&& x) noexcept +{ + + m_success = x.m_success; + return *this; +} + +bool LoadMap_Response::operator ==( + const LoadMap_Response& x) const +{ + return (m_success == x.m_success); +} + +bool LoadMap_Response::operator !=( + const LoadMap_Response& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member success + * @param _success New value for member success + */ +void LoadMap_Response::success( + bool _success) +{ + m_success = _success; +} + +/*! + * @brief This function returns the value of member success + * @return Value of member success + */ +bool LoadMap_Response::success() const +{ + return m_success; +} + +/*! + * @brief This function returns a reference to member success + * @return Reference to member success + */ +bool& LoadMap_Response::success() +{ + return m_success; +} + + + + +} // namespace srv + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "LoadMapCdrAux.ipp" + 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..28338a5daa2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMap.h @@ -0,0 +1,340 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_H_ + +#include +#include +#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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::string m_mapname; + bool m_force_reload{false}; + bool m_reset_episode_settings{true}; + uint16_t m_map_layers{65535}; + +}; + + +/*! + * @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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + bool m_success{false}; + +}; + +} // namespace srv + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapCdrAux.hpp new file mode 100644 index 00000000000..ee0f2674bef --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapCdrAux.hpp @@ -0,0 +1,82 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LoadMapCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAPCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAPCDRAUX_HPP_ + +#include "LoadMap.h" + +constexpr uint32_t carla_msgs_srv_LoadMap_Response_max_cdr_typesize {5UL}; +constexpr uint32_t carla_msgs_srv_LoadMap_Response_max_key_cdr_typesize {0UL}; + +constexpr uint32_t carla_msgs_srv_LoadMap_Request_max_cdr_typesize {268UL}; +constexpr uint32_t carla_msgs_srv_LoadMap_Request_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::LoadMap_Request& data); + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::LoadMap_Response& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAPCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapCdrAux.ipp new file mode 100644 index 00000000000..7ba17e5a32a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapCdrAux.ipp @@ -0,0 +1,263 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LoadMapCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAPCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAPCDRAUX_IPP_ + +#include "LoadMapCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::LoadMap_Request& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.mapname(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.force_reload(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.reset_episode_settings(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.map_layers(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::LoadMap_Request& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.mapname() + << eprosima::fastcdr::MemberId(1) << data.force_reload() + << eprosima::fastcdr::MemberId(2) << data.reset_episode_settings() + << eprosima::fastcdr::MemberId(3) << data.map_layers() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::LoadMap_Request& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.mapname(); + break; + + case 1: + dcdr >> data.force_reload(); + break; + + case 2: + dcdr >> data.reset_episode_settings(); + break; + + case 3: + dcdr >> data.map_layers(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::LoadMap_Request& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::LoadMap_Response& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.success(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::LoadMap_Response& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.success() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::LoadMap_Response& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.success(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::LoadMap_Response& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAPCDRAUX_IPP_ + 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..b6f7a11a2cc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapPubSubTypes.cxx @@ -0,0 +1,380 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "LoadMapPubSubTypes.h" +#include "LoadMapCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(LoadMap_Request::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_LoadMap_Request_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LoadMap_RequestPubSubType::~LoadMap_RequestPubSubType() +{ +} + +bool LoadMap_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LoadMap_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LoadMap_RequestPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + + +LoadMap_ResponsePubSubType::LoadMap_ResponsePubSubType() +{ + setName("carla_msgs::srv::dds_::LoadMap_Response_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(LoadMap_Response::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_LoadMap_Response_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LoadMap_ResponsePubSubType::~LoadMap_ResponsePubSubType() +{ +} + +bool LoadMap_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LoadMap_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LoadMap_ResponsePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..8d6451f71f3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/LoadMapPubSubTypes.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 LoadMapPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "LoadMap.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~LoadMap_RequestPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; + + + +/*! + * @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 ~LoadMap_ResponsePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_LOADMAP_PUBSUBTYPES_H_ + 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..3465804bd83 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettings.cxx @@ -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 SetEpisodeSettings.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace srv { + + + +SetEpisodeSettings_Request::SetEpisodeSettings_Request() +{ +} + +SetEpisodeSettings_Request::~SetEpisodeSettings_Request() +{ +} + +SetEpisodeSettings_Request::SetEpisodeSettings_Request( + const SetEpisodeSettings_Request& x) +{ + m_episode_settings = x.m_episode_settings; +} + +SetEpisodeSettings_Request::SetEpisodeSettings_Request( + SetEpisodeSettings_Request&& x) noexcept +{ + m_episode_settings = std::move(x.m_episode_settings); +} + +SetEpisodeSettings_Request& SetEpisodeSettings_Request::operator =( + const SetEpisodeSettings_Request& x) +{ + + m_episode_settings = x.m_episode_settings; + return *this; +} + +SetEpisodeSettings_Request& SetEpisodeSettings_Request::operator =( + SetEpisodeSettings_Request&& x) noexcept +{ + + m_episode_settings = std::move(x.m_episode_settings); + return *this; +} + +bool SetEpisodeSettings_Request::operator ==( + const SetEpisodeSettings_Request& x) const +{ + return (m_episode_settings == x.m_episode_settings); +} + +bool SetEpisodeSettings_Request::operator !=( + const SetEpisodeSettings_Request& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member episode_settings + * @param _episode_settings New value to be copied in member episode_settings + */ +void 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 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& 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& SetEpisodeSettings_Request::episode_settings() +{ + return m_episode_settings; +} + + + + +SetEpisodeSettings_Response::SetEpisodeSettings_Response() +{ +} + +SetEpisodeSettings_Response::~SetEpisodeSettings_Response() +{ +} + +SetEpisodeSettings_Response::SetEpisodeSettings_Response( + const SetEpisodeSettings_Response& x) +{ + m_success = x.m_success; +} + +SetEpisodeSettings_Response::SetEpisodeSettings_Response( + SetEpisodeSettings_Response&& x) noexcept +{ + m_success = x.m_success; +} + +SetEpisodeSettings_Response& SetEpisodeSettings_Response::operator =( + const SetEpisodeSettings_Response& x) +{ + + m_success = x.m_success; + return *this; +} + +SetEpisodeSettings_Response& SetEpisodeSettings_Response::operator =( + SetEpisodeSettings_Response&& x) noexcept +{ + + m_success = x.m_success; + return *this; +} + +bool SetEpisodeSettings_Response::operator ==( + const SetEpisodeSettings_Response& x) const +{ + return (m_success == x.m_success); +} + +bool SetEpisodeSettings_Response::operator !=( + const SetEpisodeSettings_Response& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member success + * @param _success New value for member success + */ +void SetEpisodeSettings_Response::success( + bool _success) +{ + m_success = _success; +} + +/*! + * @brief This function returns the value of member success + * @return Value of member success + */ +bool SetEpisodeSettings_Response::success() const +{ + return m_success; +} + +/*! + * @brief This function returns a reference to member success + * @return Reference to member success + */ +bool& SetEpisodeSettings_Response::success() +{ + return m_success; +} + + + + +} // namespace srv + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SetEpisodeSettingsCdrAux.ipp" + 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..5e0b7902e75 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettings.h @@ -0,0 +1,263 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "carla_msgs/msg/CarlaEpisodeSettings.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + bool m_success{false}; + +}; + +} // namespace srv + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsCdrAux.hpp new file mode 100644 index 00000000000..d6c16789774 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsCdrAux.hpp @@ -0,0 +1,59 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SetEpisodeSettingsCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGSCDRAUX_HPP_ + +#include "SetEpisodeSettings.h" + +constexpr uint32_t carla_msgs_srv_SetEpisodeSettings_Request_max_cdr_typesize {61UL}; +constexpr uint32_t carla_msgs_srv_SetEpisodeSettings_Request_max_key_cdr_typesize {0UL}; + +constexpr uint32_t carla_msgs_srv_SetEpisodeSettings_Response_max_cdr_typesize {5UL}; +constexpr uint32_t carla_msgs_srv_SetEpisodeSettings_Response_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SetEpisodeSettings_Request& data); + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SetEpisodeSettings_Response& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsCdrAux.ipp new file mode 100644 index 00000000000..f9c8d83118f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsCdrAux.ipp @@ -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 SetEpisodeSettingsCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGSCDRAUX_IPP_ + +#include "SetEpisodeSettingsCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::SetEpisodeSettings_Request& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.episode_settings(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SetEpisodeSettings_Request& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.episode_settings() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::SetEpisodeSettings_Request& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.episode_settings(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SetEpisodeSettings_Request& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::SetEpisodeSettings_Response& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.success(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SetEpisodeSettings_Response& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.success() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::SetEpisodeSettings_Response& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.success(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SetEpisodeSettings_Response& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGSCDRAUX_IPP_ + 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..76bc4d4b48e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsPubSubTypes.cxx @@ -0,0 +1,354 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SetEpisodeSettingsPubSubTypes.h" +#include "SetEpisodeSettingsCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace srv { + + +SetEpisodeSettings_RequestPubSubType::SetEpisodeSettings_RequestPubSubType() +{ + setName("carla_msgs::srv::dds_::SetEpisodeSettings_Request_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SetEpisodeSettings_Request::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_SetEpisodeSettings_Request_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SetEpisodeSettings_RequestPubSubType::~SetEpisodeSettings_RequestPubSubType() +{ +} + +bool SetEpisodeSettings_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SetEpisodeSettings_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SetEpisodeSettings_RequestPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + + +SetEpisodeSettings_ResponsePubSubType::SetEpisodeSettings_ResponsePubSubType() +{ + setName("carla_msgs::srv::dds_::SetEpisodeSettings_Response_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SetEpisodeSettings_Response::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_SetEpisodeSettings_Response_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SetEpisodeSettings_ResponsePubSubType::~SetEpisodeSettings_ResponsePubSubType() +{ +} + +bool SetEpisodeSettings_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SetEpisodeSettings_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SetEpisodeSettings_ResponsePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..2d9906066c2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SetEpisodeSettingsPubSubTypes.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 SetEpisodeSettingsPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "SetEpisodeSettings.h" + +#include "carla_msgs/msg/CarlaEpisodeSettingsPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~SetEpisodeSettings_RequestPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; + + + +/*! + * @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 ~SetEpisodeSettings_ResponsePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SETEPISODESETTINGS_PUBSUBTYPES_H_ + 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..cadb1298aa9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObject.cxx @@ -0,0 +1,376 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace carla_msgs { + +namespace srv { + + + +SpawnObject_Request::SpawnObject_Request() +{ +} + +SpawnObject_Request::~SpawnObject_Request() +{ +} + +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; +} + +SpawnObject_Request::SpawnObject_Request( + SpawnObject_Request&& x) noexcept +{ + 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; +} + +SpawnObject_Request& 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; +} + +SpawnObject_Request& SpawnObject_Request::operator =( + SpawnObject_Request&& x) noexcept +{ + + 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 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 SpawnObject_Request::operator !=( + const SpawnObject_Request& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member blueprint + * @param _blueprint New value to be copied in member blueprint + */ +void 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 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& 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& 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 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 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& 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& 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 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 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& 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 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 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& SpawnObject_Request::random_pose() +{ + return m_random_pose; +} + + + + +SpawnObject_Response::SpawnObject_Response() +{ +} + +SpawnObject_Response::~SpawnObject_Response() +{ +} + +SpawnObject_Response::SpawnObject_Response( + const SpawnObject_Response& x) +{ + m_id = x.m_id; + m_error_string = x.m_error_string; +} + +SpawnObject_Response::SpawnObject_Response( + SpawnObject_Response&& x) noexcept +{ + m_id = x.m_id; + m_error_string = std::move(x.m_error_string); +} + +SpawnObject_Response& SpawnObject_Response::operator =( + const SpawnObject_Response& x) +{ + + m_id = x.m_id; + m_error_string = x.m_error_string; + return *this; +} + +SpawnObject_Response& SpawnObject_Response::operator =( + SpawnObject_Response&& x) noexcept +{ + + m_id = x.m_id; + m_error_string = std::move(x.m_error_string); + return *this; +} + +bool SpawnObject_Response::operator ==( + const SpawnObject_Response& x) const +{ + return (m_id == x.m_id && + m_error_string == x.m_error_string); +} + +bool SpawnObject_Response::operator !=( + const SpawnObject_Response& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void 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 SpawnObject_Response::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +int32_t& 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 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 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& 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& SpawnObject_Response::error_string() +{ + return m_error_string; +} + + + + +} // namespace srv + + +} // namespace carla_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SpawnObjectCdrAux.ipp" + 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..c701ca4d44c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObject.h @@ -0,0 +1,362 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "carla_msgs/msg/CarlaActorBlueprint.h" +#include "geometry_msgs/msg/Pose.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + carla_msgs::msg::CarlaActorBlueprint m_blueprint; + geometry_msgs::msg::Pose m_transform; + uint32_t m_attach_to{0}; + bool m_random_pose{false}; + +}; + + +/*! + * @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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int32_t m_id{0}; + std::string m_error_string; + +}; + +} // namespace srv + +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectCdrAux.hpp new file mode 100644 index 00000000000..1cb4baee142 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectCdrAux.hpp @@ -0,0 +1,63 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpawnObjectCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECTCDRAUX_HPP_ + +#include "SpawnObject.h" + +constexpr uint32_t carla_msgs_srv_SpawnObject_Request_max_cdr_typesize {78765UL}; +constexpr uint32_t carla_msgs_srv_SpawnObject_Request_max_key_cdr_typesize {0UL}; + +constexpr uint32_t carla_msgs_srv_SpawnObject_Response_max_cdr_typesize {268UL}; +constexpr uint32_t carla_msgs_srv_SpawnObject_Response_max_key_cdr_typesize {0UL}; + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SpawnObject_Request& data); + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SpawnObject_Response& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectCdrAux.ipp new file mode 100644 index 00000000000..3a1c5446dc5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectCdrAux.ipp @@ -0,0 +1,248 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpawnObjectCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECTCDRAUX_IPP_ + +#include "SpawnObjectCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::SpawnObject_Request& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.blueprint(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.transform(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.attach_to(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.random_pose(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SpawnObject_Request& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.blueprint() + << eprosima::fastcdr::MemberId(1) << data.transform() + << eprosima::fastcdr::MemberId(2) << data.attach_to() + << eprosima::fastcdr::MemberId(3) << data.random_pose() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::SpawnObject_Request& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.blueprint(); + break; + + case 1: + dcdr >> data.transform(); + break; + + case 2: + dcdr >> data.attach_to(); + break; + + case 3: + dcdr >> data.random_pose(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SpawnObject_Request& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const carla_msgs::srv::SpawnObject_Response& data, + size_t& current_alignment) +{ + using namespace carla_msgs::srv; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.error_string(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SpawnObject_Response& data) +{ + using namespace carla_msgs::srv; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.id() + << eprosima::fastcdr::MemberId(1) << data.error_string() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + carla_msgs::srv::SpawnObject_Response& data) +{ + using namespace carla_msgs::srv; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.id(); + break; + + case 1: + dcdr >> data.error_string(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const carla_msgs::srv::SpawnObject_Response& data) +{ + using namespace carla_msgs::srv; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECTCDRAUX_IPP_ + 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..118d6c0f829 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectPubSubTypes.cxx @@ -0,0 +1,354 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SpawnObjectPubSubTypes.h" +#include "SpawnObjectCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace carla_msgs { +namespace srv { + + +SpawnObject_RequestPubSubType::SpawnObject_RequestPubSubType() +{ + setName("carla_msgs::srv::dds_::SpawnObject_Request_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SpawnObject_Request::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_SpawnObject_Request_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SpawnObject_RequestPubSubType::~SpawnObject_RequestPubSubType() +{ +} + +bool SpawnObject_RequestPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SpawnObject_RequestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SpawnObject_RequestPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + + +SpawnObject_ResponsePubSubType::SpawnObject_ResponsePubSubType() +{ + setName("carla_msgs::srv::dds_::SpawnObject_Response_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SpawnObject_Response::getMaxCdrSerializedSize()); +#else + carla_msgs_srv_SpawnObject_Response_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SpawnObject_ResponsePubSubType::~SpawnObject_ResponsePubSubType() +{ +} + +bool SpawnObject_ResponsePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SpawnObject_ResponsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SpawnObject_ResponsePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..1a90f669c6d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/carla_msgs/srv/SpawnObjectPubSubTypes.h @@ -0,0 +1,224 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "SpawnObject.h" + +#include "carla_msgs/msg/CarlaActorBlueprintPubSubTypes.h" +#include "geometry_msgs/msg/PosePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~SpawnObject_RequestPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; + + + +/*! + * @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 ~SpawnObject_ResponsePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace srv +} // namespace carla_msgs + +#endif // _FAST_DDS_GENERATED_CARLA_MSGS_SRV_SPAWNOBJECT_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/clean_idl_file.bash b/LibCarla/source/carla/ros2/fastdds/clean_idl_file.bash new file mode 100755 index 00000000000..04b6d060038 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/clean_idl_file.bash @@ -0,0 +1,55 @@ +#!/bin/bash + +CLEAN_FILE=$1 + +if [ -z "$CLEAN_FILE" ]; then + echo "Usage: $0 " + exit 1 +fi + +if [ ! -f "$CLEAN_FILE" ]; then + echo "Provided file '$CLEAN_FILE' not a regular file" + echo "Usage: $0 " + exit 1 +fi + +echo "--- Processing: $CLEAN_FILE ---" + +# 1. CHECK & REPLACE: #pragma once (Smart Placement) +if ! grep -qi "#pragma once" "$CLEAN_FILE"; then + # Find the line number of the first line that does NOT start with / or * + # We use grep -n to get line numbers, then head -n1 to get the first match + FIRST_CODE_LINE=$(grep -nE -v "^([[:space:]]*[/]|([[:space:]]*[*]))" "$CLEAN_FILE" | head -n1 | cut -d: -f1) + + # If the file is all comments or empty, default to line 1 + if [ -z "$FIRST_CODE_LINE" ]; then FIRST_CODE_LINE=1; fi + + # Insert at the calculated line + sed -i "${FIRST_CODE_LINE}i #pragma once\n" "$CLEAN_FILE" + echo "[ADDED] #pragma once inserted at line $FIRST_CODE_LINE (after comments)." +else + echo "[SKIP] #pragma once already present." +fi + +# 2. CHECK & REPLACE: \" with ' +# Count matches before replacement +#COUNT=$(grep -c '\\"' "$CLEAN_FILE") + +#if [ "$COUNT" -gt 0 ]; then + # Perform replacement using the safe hex code for single quote +# sed -i "s/\\\\\"/\x27/g" "$CLEAN_FILE" + + # Verify if any are left (should be 0) +# REMAINING=$(grep -c '\\"' "$CLEAN_FILE") +# SUCCESS_COUNT=$((COUNT - REMAINING)) + +# echo "[FIXED] Replaced $SUCCESS_COUNT instance(s) of escaped quotes." + +# if [ "$REMAINING" -gt 0 ]; then +# echo "[WARN] $REMAINING instances could not be replaced (check file permissions)." +# fi +#else +# echo "[SKIP] No escaped double quotes (\\\") found." +#fi + +echo "--- Finished $CLEAN_FILE ---" \ 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..1f216479402 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/Object.cxx @@ -0,0 +1,569 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace derived_object_msgs { + +namespace msg { + +namespace Object_Constants { + + +} // namespace Object_Constants + + +Object::Object() +{ +} + +Object::~Object() +{ +} + +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; +} + +Object::Object( + Object&& x) noexcept +{ + 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; +} + +Object& 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; +} + +Object& Object::operator =( + Object&& x) noexcept +{ + + 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 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 Object::operator !=( + const Object& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& Object::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& Object::header() +{ + return m_header; +} + + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void Object::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t Object::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& 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 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 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& 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 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 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& 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 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 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& Object::pose() const +{ + return m_pose; +} + +/*! + * @brief This function returns a reference to member pose + * @return Reference to member pose + */ +geometry_msgs::msg::Pose& 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 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 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& Object::twist() const +{ + return m_twist; +} + +/*! + * @brief This function returns a reference to member twist + * @return Reference to member twist + */ +geometry_msgs::msg::Twist& 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 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 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& Object::accel() const +{ + return m_accel; +} + +/*! + * @brief This function returns a reference to member accel + * @return Reference to member accel + */ +geometry_msgs::msg::Accel& 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 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 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& Object::polygon() const +{ + return m_polygon; +} + +/*! + * @brief This function returns a reference to member polygon + * @return Reference to member polygon + */ +geometry_msgs::msg::Polygon& 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 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 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& Object::shape() const +{ + return m_shape; +} + +/*! + * @brief This function returns a reference to member shape + * @return Reference to member shape + */ +shape_msgs::msg::SolidPrimitive& Object::shape() +{ + return m_shape; +} + + +/*! + * @brief This function sets a value in member classification + * @param _classification New value for member classification + */ +void Object::classification( + uint8_t _classification) +{ + m_classification = _classification; +} + +/*! + * @brief This function returns the value of member classification + * @return Value of member classification + */ +uint8_t Object::classification() const +{ + return m_classification; +} + +/*! + * @brief This function returns a reference to member classification + * @return Reference to member classification + */ +uint8_t& 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 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 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& 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 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 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& Object::classification_age() +{ + return m_classification_age; +} + + + + +} // namespace msg + + +} // namespace derived_object_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ObjectCdrAux.ipp" + 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..7a66693ea75 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/Object.h @@ -0,0 +1,466 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECT_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECT_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "geometry_msgs/msg/Polygon.h" +#include "geometry_msgs/msg/Twist.h" +#include "std_msgs/msg/Header.h" +#include "shape_msgs/msg/SolidPrimitive.h" +#include "geometry_msgs/msg/Accel.h" +#include "geometry_msgs/msg/Pose.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std_msgs::msg::Header m_header; + uint32_t m_id{0}; + uint8_t m_detection_level{0}; + bool m_object_classified{false}; + 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{0}; + uint8_t m_classification_certainty{0}; + uint32_t m_classification_age{0}; + +}; + +} // namespace msg + +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECT_H_ + + + 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..75ea503e72a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArray.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 ObjectArray.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace derived_object_msgs { + +namespace msg { + + + + + +ObjectArray::ObjectArray() +{ +} + +ObjectArray::~ObjectArray() +{ +} + +ObjectArray::ObjectArray( + const ObjectArray& x) +{ + m_header = x.m_header; + m_objects = x.m_objects; +} + +ObjectArray::ObjectArray( + ObjectArray&& x) noexcept +{ + m_header = std::move(x.m_header); + m_objects = std::move(x.m_objects); +} + +ObjectArray& ObjectArray::operator =( + const ObjectArray& x) +{ + + m_header = x.m_header; + m_objects = x.m_objects; + return *this; +} + +ObjectArray& ObjectArray::operator =( + ObjectArray&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_objects = std::move(x.m_objects); + return *this; +} + +bool ObjectArray::operator ==( + const ObjectArray& x) const +{ + return (m_header == x.m_header && + m_objects == x.m_objects); +} + +bool ObjectArray::operator !=( + const ObjectArray& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& ObjectArray::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& 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 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 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& ObjectArray::objects() const +{ + return m_objects; +} + +/*! + * @brief This function returns a reference to member objects + * @return Reference to member objects + */ +std::vector& ObjectArray::objects() +{ + return m_objects; +} + + + + +} // namespace msg + + +} // namespace derived_object_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ObjectArrayCdrAux.ipp" + 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..791c0bd2c0f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArray.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 ObjectArray.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAY_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAY_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "Object.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayCdrAux.hpp new file mode 100644 index 00000000000..64fb884f10d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayCdrAux.hpp @@ -0,0 +1,58 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ObjectArrayCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAYCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAYCDRAUX_HPP_ + +#include "ObjectArray.h" + +constexpr uint32_t derived_object_msgs_msg_ObjectArray_max_cdr_typesize {376284UL}; +constexpr uint32_t derived_object_msgs_msg_ObjectArray_max_key_cdr_typesize {0UL}; + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::ObjectArray& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAYCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayCdrAux.ipp new file mode 100644 index 00000000000..cf2b2cae671 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayCdrAux.ipp @@ -0,0 +1,140 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ObjectArrayCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAYCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAYCDRAUX_IPP_ + +#include "ObjectArrayCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const derived_object_msgs::msg::ObjectArray& data, + size_t& current_alignment) +{ + using namespace derived_object_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.objects(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::ObjectArray& data) +{ + using namespace derived_object_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.objects() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + derived_object_msgs::msg::ObjectArray& data) +{ + using namespace derived_object_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.objects(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::ObjectArray& data) +{ + using namespace derived_object_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAYCDRAUX_IPP_ + 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..1582126cc95 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayPubSubTypes.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 ObjectArrayPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ObjectArrayPubSubTypes.h" +#include "ObjectArrayCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace derived_object_msgs { +namespace msg { + + + + +ObjectArrayPubSubType::ObjectArrayPubSubType() +{ + setName("derived_object_msgs::msg::dds_::ObjectArray_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ObjectArray::getMaxCdrSerializedSize()); +#else + derived_object_msgs_msg_ObjectArray_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ObjectArrayPubSubType::~ObjectArrayPubSubType() +{ +} + +bool ObjectArrayPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ObjectArrayPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ObjectArrayPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..8e070d02d21 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectArrayPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ObjectArray.h" + +#include "ObjectPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~ObjectArrayPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTARRAY_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectCdrAux.hpp new file mode 100644 index 00000000000..3b26c70c9ab --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectCdrAux.hpp @@ -0,0 +1,82 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ObjectCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTCDRAUX_HPP_ + +#include "Object.h" + +constexpr uint32_t derived_object_msgs_msg_Object_max_cdr_typesize {3756UL}; +constexpr uint32_t derived_object_msgs_msg_Object_max_key_cdr_typesize {0UL}; + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::Object& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectCdrAux.ipp new file mode 100644 index 00000000000..cd3795519af --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectCdrAux.ipp @@ -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 ObjectCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTCDRAUX_IPP_ + +#include "ObjectCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const derived_object_msgs::msg::Object& data, + size_t& current_alignment) +{ + using namespace derived_object_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.detection_level(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.object_classified(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.pose(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.twist(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.accel(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.polygon(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.shape(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), + data.classification(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(10), + data.classification_certainty(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(11), + data.classification_age(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::Object& data) +{ + using namespace derived_object_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.id() + << eprosima::fastcdr::MemberId(2) << data.detection_level() + << eprosima::fastcdr::MemberId(3) << data.object_classified() + << eprosima::fastcdr::MemberId(4) << data.pose() + << eprosima::fastcdr::MemberId(5) << data.twist() + << eprosima::fastcdr::MemberId(6) << data.accel() + << eprosima::fastcdr::MemberId(7) << data.polygon() + << eprosima::fastcdr::MemberId(8) << data.shape() + << eprosima::fastcdr::MemberId(9) << data.classification() + << eprosima::fastcdr::MemberId(10) << data.classification_certainty() + << eprosima::fastcdr::MemberId(11) << data.classification_age() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + derived_object_msgs::msg::Object& data) +{ + using namespace derived_object_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.id(); + break; + + case 2: + dcdr >> data.detection_level(); + break; + + case 3: + dcdr >> data.object_classified(); + break; + + case 4: + dcdr >> data.pose(); + break; + + case 5: + dcdr >> data.twist(); + break; + + case 6: + dcdr >> data.accel(); + break; + + case 7: + dcdr >> data.polygon(); + break; + + case 8: + dcdr >> data.shape(); + break; + + case 9: + dcdr >> data.classification(); + break; + + case 10: + dcdr >> data.classification_certainty(); + break; + + case 11: + dcdr >> data.classification_age(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::Object& data) +{ + using namespace derived_object_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTCDRAUX_IPP_ + 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..2df23c80e9c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectPubSubTypes.cxx @@ -0,0 +1,230 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ObjectPubSubTypes.h" +#include "ObjectCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace derived_object_msgs { +namespace msg { +namespace Object_Constants { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} //End of namespace Object_Constants + + + +ObjectPubSubType::ObjectPubSubType() +{ + setName("derived_object_msgs::msg::dds_::Object_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Object::getMaxCdrSerializedSize()); +#else + derived_object_msgs_msg_Object_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ObjectPubSubType::~ObjectPubSubType() +{ +} + +bool ObjectPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ObjectPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ObjectPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..78df9f8c5b4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectPubSubTypes.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 ObjectPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "Object.h" + +#include "geometry_msgs/msg/PolygonPubSubTypes.h" +#include "geometry_msgs/msg/TwistPubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" +#include "shape_msgs/msg/SolidPrimitivePubSubTypes.h" +#include "geometry_msgs/msg/AccelPubSubTypes.h" +#include "geometry_msgs/msg/PosePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~ObjectPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECT_PUBSUBTYPES_H_ + 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..65dee47d1c4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariance.cxx @@ -0,0 +1,569 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace derived_object_msgs { + +namespace msg { + +namespace ObjectWithCovariance_Constants { + + +} // namespace ObjectWithCovariance_Constants + + +ObjectWithCovariance::ObjectWithCovariance() +{ +} + +ObjectWithCovariance::~ObjectWithCovariance() +{ +} + +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; +} + +ObjectWithCovariance::ObjectWithCovariance( + ObjectWithCovariance&& x) noexcept +{ + 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; +} + +ObjectWithCovariance& 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; +} + +ObjectWithCovariance& ObjectWithCovariance::operator =( + ObjectWithCovariance&& x) noexcept +{ + + 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 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 ObjectWithCovariance::operator !=( + const ObjectWithCovariance& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& ObjectWithCovariance::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& ObjectWithCovariance::header() +{ + return m_header; +} + + +/*! + * @brief This function sets a value in member id + * @param _id New value for member id + */ +void ObjectWithCovariance::id( + uint32_t _id) +{ + m_id = _id; +} + +/*! + * @brief This function returns the value of member id + * @return Value of member id + */ +uint32_t ObjectWithCovariance::id() const +{ + return m_id; +} + +/*! + * @brief This function returns a reference to member id + * @return Reference to member id + */ +uint32_t& 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 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 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& 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 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 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& 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 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 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& ObjectWithCovariance::pose() const +{ + return m_pose; +} + +/*! + * @brief This function returns a reference to member pose + * @return Reference to member pose + */ +geometry_msgs::msg::PoseWithCovariance& 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 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 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& ObjectWithCovariance::twist() const +{ + return m_twist; +} + +/*! + * @brief This function returns a reference to member twist + * @return Reference to member twist + */ +geometry_msgs::msg::TwistWithCovariance& 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 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 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& ObjectWithCovariance::accel() const +{ + return m_accel; +} + +/*! + * @brief This function returns a reference to member accel + * @return Reference to member accel + */ +geometry_msgs::msg::AccelWithCovariance& 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 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 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& ObjectWithCovariance::polygon() const +{ + return m_polygon; +} + +/*! + * @brief This function returns a reference to member polygon + * @return Reference to member polygon + */ +geometry_msgs::msg::Polygon& 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 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 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& 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& ObjectWithCovariance::shape() +{ + return m_shape; +} + + +/*! + * @brief This function sets a value in member classification + * @param _classification New value for member classification + */ +void ObjectWithCovariance::classification( + uint8_t _classification) +{ + m_classification = _classification; +} + +/*! + * @brief This function returns the value of member classification + * @return Value of member classification + */ +uint8_t ObjectWithCovariance::classification() const +{ + return m_classification; +} + +/*! + * @brief This function returns a reference to member classification + * @return Reference to member classification + */ +uint8_t& 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 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 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& 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 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 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& ObjectWithCovariance::classification_age() +{ + return m_classification_age; +} + + + + +} // namespace msg + + +} // namespace derived_object_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ObjectWithCovarianceCdrAux.ipp" + 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..4c37bc9644d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariance.h @@ -0,0 +1,466 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCE_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#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" + + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std_msgs::msg::Header m_header; + uint32_t m_id{0}; + uint8_t m_detection_level{0}; + bool m_object_classified{false}; + 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{0}; + uint8_t m_classification_certainty{0}; + uint32_t m_classification_age{0}; + +}; + +} // namespace msg + +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCE_H_ + + + 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..2d27c0a82ec --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArray.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 ObjectWithCovarianceArray.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace derived_object_msgs { + +namespace msg { + + + + + +ObjectWithCovarianceArray::ObjectWithCovarianceArray() +{ +} + +ObjectWithCovarianceArray::~ObjectWithCovarianceArray() +{ +} + +ObjectWithCovarianceArray::ObjectWithCovarianceArray( + const ObjectWithCovarianceArray& x) +{ + m_header = x.m_header; + m_objects = x.m_objects; +} + +ObjectWithCovarianceArray::ObjectWithCovarianceArray( + ObjectWithCovarianceArray&& x) noexcept +{ + m_header = std::move(x.m_header); + m_objects = std::move(x.m_objects); +} + +ObjectWithCovarianceArray& ObjectWithCovarianceArray::operator =( + const ObjectWithCovarianceArray& x) +{ + + m_header = x.m_header; + m_objects = x.m_objects; + return *this; +} + +ObjectWithCovarianceArray& ObjectWithCovarianceArray::operator =( + ObjectWithCovarianceArray&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_objects = std::move(x.m_objects); + return *this; +} + +bool ObjectWithCovarianceArray::operator ==( + const ObjectWithCovarianceArray& x) const +{ + return (m_header == x.m_header && + m_objects == x.m_objects); +} + +bool ObjectWithCovarianceArray::operator !=( + const ObjectWithCovarianceArray& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& ObjectWithCovarianceArray::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& 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 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 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& ObjectWithCovarianceArray::objects() const +{ + return m_objects; +} + +/*! + * @brief This function returns a reference to member objects + * @return Reference to member objects + */ +std::vector& ObjectWithCovarianceArray::objects() +{ + return m_objects; +} + + + + +} // namespace msg + + +} // namespace derived_object_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ObjectWithCovarianceArrayCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArray.h b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArray.h new file mode 100644 index 00000000000..eb42530be31 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArray.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 ObjectWithCovarianceArray.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAY_H_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAY_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ObjectWithCovariance.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(OBJECTWITHCOVARIANCEARRAY_SOURCE) +#define OBJECTWITHCOVARIANCEARRAY_DllAPI __declspec( dllexport ) +#else +#define OBJECTWITHCOVARIANCEARRAY_DllAPI __declspec( dllimport ) +#endif // OBJECTWITHCOVARIANCEARRAY_SOURCE +#else +#define OBJECTWITHCOVARIANCEARRAY_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define OBJECTWITHCOVARIANCEARRAY_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace derived_object_msgs { + +namespace msg { + + + + + +/*! + * @brief This class represents the structure ObjectWithCovarianceArray defined by the user in the IDL file. + * @ingroup ObjectWithCovarianceArray + */ +class ObjectWithCovarianceArray +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport ObjectWithCovarianceArray(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~ObjectWithCovarianceArray(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovarianceArray that will be copied. + */ + eProsima_user_DllExport ObjectWithCovarianceArray( + const ObjectWithCovarianceArray& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovarianceArray that will be copied. + */ + eProsima_user_DllExport ObjectWithCovarianceArray( + ObjectWithCovarianceArray&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovarianceArray that will be copied. + */ + eProsima_user_DllExport ObjectWithCovarianceArray& operator =( + const ObjectWithCovarianceArray& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object derived_object_msgs::msg::ObjectWithCovarianceArray that will be copied. + */ + eProsima_user_DllExport ObjectWithCovarianceArray& operator =( + ObjectWithCovarianceArray&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x derived_object_msgs::msg::ObjectWithCovarianceArray object to compare. + */ + eProsima_user_DllExport bool operator ==( + const ObjectWithCovarianceArray& x) const; + + /*! + * @brief Comparison operator. + * @param x derived_object_msgs::msg::ObjectWithCovarianceArray object to compare. + */ + eProsima_user_DllExport bool operator !=( + const ObjectWithCovarianceArray& 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(); + +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_OBJECTWITHCOVARIANCEARRAY_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayCdrAux.hpp new file mode 100644 index 00000000000..9d37833b10f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayCdrAux.hpp @@ -0,0 +1,67 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ObjectWithCovarianceArrayCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAYCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAYCDRAUX_HPP_ + +#include "ObjectWithCovarianceArray.h" + +constexpr uint32_t derived_object_msgs_msg_ObjectWithCovarianceArray_max_cdr_typesize {461888UL}; +constexpr uint32_t derived_object_msgs_msg_ObjectWithCovarianceArray_max_key_cdr_typesize {0UL}; + + + + + + + + + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::ObjectWithCovarianceArray& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAYCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayCdrAux.ipp new file mode 100644 index 00000000000..294f1897b93 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayCdrAux.ipp @@ -0,0 +1,140 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ObjectWithCovarianceArrayCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAYCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAYCDRAUX_IPP_ + +#include "ObjectWithCovarianceArrayCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const derived_object_msgs::msg::ObjectWithCovarianceArray& data, + size_t& current_alignment) +{ + using namespace derived_object_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.objects(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::ObjectWithCovarianceArray& data) +{ + using namespace derived_object_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.objects() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + derived_object_msgs::msg::ObjectWithCovarianceArray& data) +{ + using namespace derived_object_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.objects(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::ObjectWithCovarianceArray& data) +{ + using namespace derived_object_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAYCDRAUX_IPP_ + 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..24cbfe771f2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayPubSubTypes.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 ObjectWithCovarianceArrayPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ObjectWithCovarianceArrayPubSubTypes.h" +#include "ObjectWithCovarianceArrayCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace derived_object_msgs { +namespace msg { + + + + +ObjectWithCovarianceArrayPubSubType::ObjectWithCovarianceArrayPubSubType() +{ + setName("derived_object_msgs::msg::dds_::ObjectWithCovarianceArray_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ObjectWithCovarianceArray::getMaxCdrSerializedSize()); +#else + derived_object_msgs_msg_ObjectWithCovarianceArray_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ObjectWithCovarianceArrayPubSubType::~ObjectWithCovarianceArrayPubSubType() +{ +} + +bool ObjectWithCovarianceArrayPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ObjectWithCovarianceArrayPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ObjectWithCovarianceArrayPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..0935f587241 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceArrayPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ObjectWithCovarianceArray.h" + +#include "ObjectWithCovariancePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~ObjectWithCovarianceArrayPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCEARRAY_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceCdrAux.hpp new file mode 100644 index 00000000000..69db62db34c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceCdrAux.hpp @@ -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 ObjectWithCovarianceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCECDRAUX_HPP_ + +#include "ObjectWithCovariance.h" + +constexpr uint32_t derived_object_msgs_msg_ObjectWithCovariance_max_cdr_typesize {4616UL}; +constexpr uint32_t derived_object_msgs_msg_ObjectWithCovariance_max_key_cdr_typesize {0UL}; + + + + + + + + + + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::ObjectWithCovariance& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceCdrAux.ipp new file mode 100644 index 00000000000..f00dfaa253c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovarianceCdrAux.ipp @@ -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 ObjectWithCovarianceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCECDRAUX_IPP_ + +#include "ObjectWithCovarianceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const derived_object_msgs::msg::ObjectWithCovariance& data, + size_t& current_alignment) +{ + using namespace derived_object_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.detection_level(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.object_classified(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.pose(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.twist(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.accel(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.polygon(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.shape(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), + data.classification(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(10), + data.classification_certainty(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(11), + data.classification_age(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::ObjectWithCovariance& data) +{ + using namespace derived_object_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.id() + << eprosima::fastcdr::MemberId(2) << data.detection_level() + << eprosima::fastcdr::MemberId(3) << data.object_classified() + << eprosima::fastcdr::MemberId(4) << data.pose() + << eprosima::fastcdr::MemberId(5) << data.twist() + << eprosima::fastcdr::MemberId(6) << data.accel() + << eprosima::fastcdr::MemberId(7) << data.polygon() + << eprosima::fastcdr::MemberId(8) << data.shape() + << eprosima::fastcdr::MemberId(9) << data.classification() + << eprosima::fastcdr::MemberId(10) << data.classification_certainty() + << eprosima::fastcdr::MemberId(11) << data.classification_age() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + derived_object_msgs::msg::ObjectWithCovariance& data) +{ + using namespace derived_object_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.id(); + break; + + case 2: + dcdr >> data.detection_level(); + break; + + case 3: + dcdr >> data.object_classified(); + break; + + case 4: + dcdr >> data.pose(); + break; + + case 5: + dcdr >> data.twist(); + break; + + case 6: + dcdr >> data.accel(); + break; + + case 7: + dcdr >> data.polygon(); + break; + + case 8: + dcdr >> data.shape(); + break; + + case 9: + dcdr >> data.classification(); + break; + + case 10: + dcdr >> data.classification_certainty(); + break; + + case 11: + dcdr >> data.classification_age(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::ObjectWithCovariance& data) +{ + using namespace derived_object_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCECDRAUX_IPP_ + 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..a7149ab09dc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariancePubSubTypes.cxx @@ -0,0 +1,230 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ObjectWithCovariancePubSubTypes.h" +#include "ObjectWithCovarianceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace derived_object_msgs { +namespace msg { +namespace ObjectWithCovariance_Constants { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} //End of namespace ObjectWithCovariance_Constants + + + +ObjectWithCovariancePubSubType::ObjectWithCovariancePubSubType() +{ + setName("derived_object_msgs::msg::dds_::ObjectWithCovariance_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ObjectWithCovariance::getMaxCdrSerializedSize()); +#else + derived_object_msgs_msg_ObjectWithCovariance_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ObjectWithCovariancePubSubType::~ObjectWithCovariancePubSubType() +{ +} + +bool ObjectWithCovariancePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ObjectWithCovariancePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ObjectWithCovariancePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..7f6bc2bed86 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/ObjectWithCovariancePubSubTypes.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 ObjectWithCovariancePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ObjectWithCovariance.h" + +#include "geometry_msgs/msg/PoseWithCovariancePubSubTypes.h" +#include "geometry_msgs/msg/TwistWithCovariancePubSubTypes.h" +#include "SolidPrimitiveWithCovariancePubSubTypes.h" +#include "geometry_msgs/msg/PolygonPubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" +#include "geometry_msgs/msg/AccelWithCovariancePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~ObjectWithCovariancePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_OBJECTWITHCOVARIANCE_PUBSUBTYPES_H_ + 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..757c8874c77 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariance.cxx @@ -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 SolidPrimitiveWithCovariance.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace derived_object_msgs { + +namespace msg { + +namespace SolidPrimitiveWithCovariance_Constants { + + +} // namespace SolidPrimitiveWithCovariance_Constants + + + + +SolidPrimitiveWithCovariance::SolidPrimitiveWithCovariance() +{ +} + +SolidPrimitiveWithCovariance::~SolidPrimitiveWithCovariance() +{ +} + +SolidPrimitiveWithCovariance::SolidPrimitiveWithCovariance( + const SolidPrimitiveWithCovariance& x) +{ + m_type = x.m_type; + m_dimensions = x.m_dimensions; + m_covariance = x.m_covariance; +} + +SolidPrimitiveWithCovariance::SolidPrimitiveWithCovariance( + SolidPrimitiveWithCovariance&& x) noexcept +{ + m_type = x.m_type; + m_dimensions = std::move(x.m_dimensions); + m_covariance = std::move(x.m_covariance); +} + +SolidPrimitiveWithCovariance& SolidPrimitiveWithCovariance::operator =( + const SolidPrimitiveWithCovariance& x) +{ + + m_type = x.m_type; + m_dimensions = x.m_dimensions; + m_covariance = x.m_covariance; + return *this; +} + +SolidPrimitiveWithCovariance& SolidPrimitiveWithCovariance::operator =( + SolidPrimitiveWithCovariance&& x) noexcept +{ + + m_type = x.m_type; + m_dimensions = std::move(x.m_dimensions); + m_covariance = std::move(x.m_covariance); + return *this; +} + +bool SolidPrimitiveWithCovariance::operator ==( + const SolidPrimitiveWithCovariance& x) const +{ + return (m_type == x.m_type && + m_dimensions == x.m_dimensions && + m_covariance == x.m_covariance); +} + +bool SolidPrimitiveWithCovariance::operator !=( + const SolidPrimitiveWithCovariance& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member type + * @param _type New value for member type + */ +void SolidPrimitiveWithCovariance::type( + uint8_t _type) +{ + m_type = _type; +} + +/*! + * @brief This function returns the value of member type + * @return Value of member type + */ +uint8_t SolidPrimitiveWithCovariance::type() const +{ + return m_type; +} + +/*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ +uint8_t& 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 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 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& SolidPrimitiveWithCovariance::dimensions() const +{ + return m_dimensions; +} + +/*! + * @brief This function returns a reference to member dimensions + * @return Reference to member dimensions + */ +std::vector& 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 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 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& SolidPrimitiveWithCovariance::covariance() const +{ + return m_covariance; +} + +/*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ +std::vector& SolidPrimitiveWithCovariance::covariance() +{ + return m_covariance; +} + + + + +} // namespace msg + + +} // namespace derived_object_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SolidPrimitiveWithCovarianceCdrAux.ipp" + 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..a1091033e5f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariance.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 SolidPrimitiveWithCovariance.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_type{0}; + std::vector m_dimensions; + std::vector m_covariance; + +}; + +} // namespace msg + +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovarianceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovarianceCdrAux.hpp new file mode 100644 index 00000000000..18ecbad3251 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovarianceCdrAux.hpp @@ -0,0 +1,77 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SolidPrimitiveWithCovarianceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCECDRAUX_HPP_ + +#include "SolidPrimitiveWithCovariance.h" + +constexpr uint32_t derived_object_msgs_msg_SolidPrimitiveWithCovariance_max_cdr_typesize {1624UL}; +constexpr uint32_t derived_object_msgs_msg_SolidPrimitiveWithCovariance_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::SolidPrimitiveWithCovariance& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovarianceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovarianceCdrAux.ipp new file mode 100644 index 00000000000..8045296c745 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovarianceCdrAux.ipp @@ -0,0 +1,173 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SolidPrimitiveWithCovarianceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCECDRAUX_IPP_ + +#include "SolidPrimitiveWithCovarianceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const derived_object_msgs::msg::SolidPrimitiveWithCovariance& data, + size_t& current_alignment) +{ + using namespace derived_object_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.dimensions(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.covariance(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::SolidPrimitiveWithCovariance& data) +{ + using namespace derived_object_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.type() + << eprosima::fastcdr::MemberId(1) << data.dimensions() + << eprosima::fastcdr::MemberId(2) << data.covariance() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + derived_object_msgs::msg::SolidPrimitiveWithCovariance& data) +{ + using namespace derived_object_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.type(); + break; + + case 1: + dcdr >> data.dimensions(); + break; + + case 2: + dcdr >> data.covariance(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const derived_object_msgs::msg::SolidPrimitiveWithCovariance& data) +{ + using namespace derived_object_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCECDRAUX_IPP_ + 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..3c0bc11dcbf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariancePubSubTypes.cxx @@ -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 SolidPrimitiveWithCovariancePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SolidPrimitiveWithCovariancePubSubTypes.h" +#include "SolidPrimitiveWithCovarianceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace derived_object_msgs { +namespace msg { +namespace SolidPrimitiveWithCovariance_Constants { + + + + + + + + + + + + + + + + + + + + + + + + + +} //End of namespace SolidPrimitiveWithCovariance_Constants + + + + + +SolidPrimitiveWithCovariancePubSubType::SolidPrimitiveWithCovariancePubSubType() +{ + setName("derived_object_msgs::msg::dds_::SolidPrimitiveWithCovariance_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SolidPrimitiveWithCovariance::getMaxCdrSerializedSize()); +#else + derived_object_msgs_msg_SolidPrimitiveWithCovariance_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SolidPrimitiveWithCovariancePubSubType::~SolidPrimitiveWithCovariancePubSubType() +{ +} + +bool SolidPrimitiveWithCovariancePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SolidPrimitiveWithCovariancePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SolidPrimitiveWithCovariancePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..c85969d88f4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/derived_object_msgs/msg/SolidPrimitiveWithCovariancePubSubTypes.h @@ -0,0 +1,163 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SolidPrimitiveWithCovariance.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~SolidPrimitiveWithCovariancePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace derived_object_msgs + +#endif // _FAST_DDS_GENERATED_DERIVED_OBJECT_MSGS_MSG_SOLIDPRIMITIVEWITHCOVARIANCE_PUBSUBTYPES_H_ + 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..fbb0f008759 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValue.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 KeyValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace diagnostic_msgs { + +namespace msg { + + + +KeyValue::KeyValue() +{ +} + +KeyValue::~KeyValue() +{ +} + +KeyValue::KeyValue( + const KeyValue& x) +{ + m_key = x.m_key; + m_value = x.m_value; +} + +KeyValue::KeyValue( + KeyValue&& x) noexcept +{ + m_key = std::move(x.m_key); + m_value = std::move(x.m_value); +} + +KeyValue& KeyValue::operator =( + const KeyValue& x) +{ + + m_key = x.m_key; + m_value = x.m_value; + return *this; +} + +KeyValue& KeyValue::operator =( + KeyValue&& x) noexcept +{ + + m_key = std::move(x.m_key); + m_value = std::move(x.m_value); + return *this; +} + +bool KeyValue::operator ==( + const KeyValue& x) const +{ + return (m_key == x.m_key && + m_value == x.m_value); +} + +bool KeyValue::operator !=( + const KeyValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member key + * @param _key New value to be copied in member key + */ +void 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 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& KeyValue::key() const +{ + return m_key; +} + +/*! + * @brief This function returns a reference to member key + * @return Reference to member key + */ +std::string& 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 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 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& KeyValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::string& KeyValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace diagnostic_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "KeyValueCdrAux.ipp" + 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..0fc17be8420 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValue.h @@ -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 KeyValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_H_ +#define _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_H_ + +#include +#include +#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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::string m_key; + std::string m_value; + +}; + +} // namespace msg + +} // namespace diagnostic_msgs + +#endif // _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValueCdrAux.hpp new file mode 100644 index 00000000000..3d552a173e0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValueCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file KeyValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUECDRAUX_HPP_ + +#include "KeyValue.h" + +constexpr uint32_t diagnostic_msgs_msg_KeyValue_max_cdr_typesize {524UL}; +constexpr uint32_t diagnostic_msgs_msg_KeyValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const diagnostic_msgs::msg::KeyValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValueCdrAux.ipp new file mode 100644 index 00000000000..4d41fd8bc87 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValueCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file KeyValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUECDRAUX_IPP_ + +#include "KeyValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const diagnostic_msgs::msg::KeyValue& data, + size_t& current_alignment) +{ + using namespace diagnostic_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.key(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const diagnostic_msgs::msg::KeyValue& data) +{ + using namespace diagnostic_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.key() + << eprosima::fastcdr::MemberId(1) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + diagnostic_msgs::msg::KeyValue& data) +{ + using namespace diagnostic_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.key(); + break; + + case 1: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const diagnostic_msgs::msg::KeyValue& data) +{ + using namespace diagnostic_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUECDRAUX_IPP_ + 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..e7283e64618 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValuePubSubTypes.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 KeyValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "KeyValuePubSubTypes.h" +#include "KeyValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace diagnostic_msgs { +namespace msg { + + +KeyValuePubSubType::KeyValuePubSubType() +{ + setName("diagnostic_msgs::msg::dds_::KeyValue_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(KeyValue::getMaxCdrSerializedSize()); +#else + diagnostic_msgs_msg_KeyValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +KeyValuePubSubType::~KeyValuePubSubType() +{ +} + +bool KeyValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool KeyValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function KeyValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..1a4c072f66a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/diagnostic_msgs/msg/KeyValuePubSubTypes.h @@ -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 KeyValuePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "KeyValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~KeyValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace diagnostic_msgs + +#endif // _FAST_DDS_GENERATED_DIAGNOSTIC_MSGS_MSG_KEYVALUE_PUBSUBTYPES_H_ + 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..2f15546539e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidence.cxx @@ -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 AccelerationConfidence.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace AccelerationConfidence_Constants { + + +} // namespace AccelerationConfidence_Constants + + +AccelerationConfidence::AccelerationConfidence() +{ +} + +AccelerationConfidence::~AccelerationConfidence() +{ +} + +AccelerationConfidence::AccelerationConfidence( + const AccelerationConfidence& x) +{ + m_value = x.m_value; +} + +AccelerationConfidence::AccelerationConfidence( + AccelerationConfidence&& x) noexcept +{ + m_value = x.m_value; +} + +AccelerationConfidence& AccelerationConfidence::operator =( + const AccelerationConfidence& x) +{ + + m_value = x.m_value; + return *this; +} + +AccelerationConfidence& AccelerationConfidence::operator =( + AccelerationConfidence&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool AccelerationConfidence::operator ==( + const AccelerationConfidence& x) const +{ + return (m_value == x.m_value); +} + +bool AccelerationConfidence::operator !=( + const AccelerationConfidence& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void AccelerationConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t AccelerationConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& AccelerationConfidence::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "AccelerationConfidenceCdrAux.ipp" + 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..75ed7d561d0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidence.h @@ -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 AccelerationConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidenceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidenceCdrAux.hpp new file mode 100644 index 00000000000..d3cb92fb844 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidenceCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AccelerationConfidenceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCECDRAUX_HPP_ + +#include "AccelerationConfidence.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_AccelerationConfidence_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_AccelerationConfidence_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AccelerationConfidence& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidenceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidenceCdrAux.ipp new file mode 100644 index 00000000000..f98135584df --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidenceCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AccelerationConfidenceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCECDRAUX_IPP_ + +#include "AccelerationConfidenceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::AccelerationConfidence& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AccelerationConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::AccelerationConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AccelerationConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCECDRAUX_IPP_ + 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..932212071dc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidencePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "AccelerationConfidencePubSubTypes.h" +#include "AccelerationConfidenceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(AccelerationConfidence::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_AccelerationConfidence_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +AccelerationConfidencePubSubType::~AccelerationConfidencePubSubType() +{ +} + +bool AccelerationConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool AccelerationConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function AccelerationConfidencePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..2f47d89b1bd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationConfidencePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "AccelerationConfidence.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~AccelerationConfidencePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONFIDENCE_PUBSUBTYPES_H_ + 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..3ad9c3cd699 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControl.cxx @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace AccelerationControl_Constants { + + +} // namespace AccelerationControl_Constants + + +AccelerationControl::AccelerationControl() +{ +} + +AccelerationControl::~AccelerationControl() +{ +} + +AccelerationControl::AccelerationControl( + const AccelerationControl& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +AccelerationControl::AccelerationControl( + AccelerationControl&& x) noexcept +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +AccelerationControl& AccelerationControl::operator =( + const AccelerationControl& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + return *this; +} + +AccelerationControl& AccelerationControl::operator =( + AccelerationControl&& x) noexcept +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + return *this; +} + +bool AccelerationControl::operator ==( + const AccelerationControl& x) const +{ + return (m_value == x.m_value && + m_bits_unused == x.m_bits_unused); +} + +bool AccelerationControl::operator !=( + const AccelerationControl& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void 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 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& AccelerationControl::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& 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 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 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& AccelerationControl::bits_unused() +{ + return m_bits_unused; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "AccelerationControlCdrAux.ipp" + 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..16b760bb5c8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControl.h @@ -0,0 +1,209 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_value; + uint8_t m_bits_unused{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROL_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlCdrAux.hpp new file mode 100644 index 00000000000..a7900a9d01e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlCdrAux.hpp @@ -0,0 +1,67 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AccelerationControlCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROLCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROLCDRAUX_HPP_ + +#include "AccelerationControl.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_AccelerationControl_max_cdr_typesize {109UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_AccelerationControl_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AccelerationControl& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROLCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlCdrAux.ipp new file mode 100644 index 00000000000..47831a367f0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlCdrAux.ipp @@ -0,0 +1,155 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AccelerationControlCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROLCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROLCDRAUX_IPP_ + +#include "AccelerationControlCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::AccelerationControl& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.bits_unused(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AccelerationControl& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() + << eprosima::fastcdr::MemberId(1) << data.bits_unused() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::AccelerationControl& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + case 1: + dcdr >> data.bits_unused(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AccelerationControl& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROLCDRAUX_IPP_ + 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..88a4bf20b3b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlPubSubTypes.cxx @@ -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 AccelerationControlPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "AccelerationControlPubSubTypes.h" +#include "AccelerationControlCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(AccelerationControl::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_AccelerationControl_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +AccelerationControlPubSubType::~AccelerationControlPubSubType() +{ +} + +bool AccelerationControlPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool AccelerationControlPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function AccelerationControlPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..52136ff642a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AccelerationControlPubSubTypes.h @@ -0,0 +1,153 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "AccelerationControl.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + +} // 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 ~AccelerationControlPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ACCELERATIONCONTROL_PUBSUBTYPES_H_ + 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..fb03785e0ce --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Altitude.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 Altitude.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +Altitude::Altitude() +{ +} + +Altitude::~Altitude() +{ +} + +Altitude::Altitude( + const Altitude& x) +{ + m_altitude_value = x.m_altitude_value; + m_altitude_confidence = x.m_altitude_confidence; +} + +Altitude::Altitude( + Altitude&& x) noexcept +{ + m_altitude_value = std::move(x.m_altitude_value); + m_altitude_confidence = std::move(x.m_altitude_confidence); +} + +Altitude& Altitude::operator =( + const Altitude& x) +{ + + m_altitude_value = x.m_altitude_value; + m_altitude_confidence = x.m_altitude_confidence; + return *this; +} + +Altitude& Altitude::operator =( + Altitude&& x) noexcept +{ + + m_altitude_value = std::move(x.m_altitude_value); + m_altitude_confidence = std::move(x.m_altitude_confidence); + return *this; +} + +bool Altitude::operator ==( + const Altitude& x) const +{ + return (m_altitude_value == x.m_altitude_value && + m_altitude_confidence == x.m_altitude_confidence); +} + +bool Altitude::operator !=( + const Altitude& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member altitude_value + * @param _altitude_value New value to be copied in member altitude_value + */ +void 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 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& 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& 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 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 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& 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& Altitude::altitude_confidence() +{ + return m_altitude_confidence; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "AltitudeCdrAux.ipp" + 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..dd65a6f29bf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Altitude.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "AltitudeConfidence.h" +#include "AltitudeValue.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeCdrAux.hpp new file mode 100644 index 00000000000..4aa420c01d9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AltitudeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECDRAUX_HPP_ + +#include "Altitude.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_Altitude_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_Altitude_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Altitude& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeCdrAux.ipp new file mode 100644 index 00000000000..e11a6727863 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AltitudeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECDRAUX_IPP_ + +#include "AltitudeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::Altitude& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.altitude_value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.altitude_confidence(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Altitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.altitude_value() + << eprosima::fastcdr::MemberId(1) << data.altitude_confidence() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::Altitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.altitude_value(); + break; + + case 1: + dcdr >> data.altitude_confidence(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Altitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECDRAUX_IPP_ + 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..edff54a059b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidence.cxx @@ -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 AltitudeConfidence.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace AltitudeConfidence_Constants { + + +} // namespace AltitudeConfidence_Constants + + +AltitudeConfidence::AltitudeConfidence() +{ +} + +AltitudeConfidence::~AltitudeConfidence() +{ +} + +AltitudeConfidence::AltitudeConfidence( + const AltitudeConfidence& x) +{ + m_value = x.m_value; +} + +AltitudeConfidence::AltitudeConfidence( + AltitudeConfidence&& x) noexcept +{ + m_value = x.m_value; +} + +AltitudeConfidence& AltitudeConfidence::operator =( + const AltitudeConfidence& x) +{ + + m_value = x.m_value; + return *this; +} + +AltitudeConfidence& AltitudeConfidence::operator =( + AltitudeConfidence&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool AltitudeConfidence::operator ==( + const AltitudeConfidence& x) const +{ + return (m_value == x.m_value); +} + +bool AltitudeConfidence::operator !=( + const AltitudeConfidence& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void AltitudeConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t AltitudeConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& AltitudeConfidence::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "AltitudeConfidenceCdrAux.ipp" + 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..3ef6e186e0b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidence.h @@ -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 AltitudeConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidenceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidenceCdrAux.hpp new file mode 100644 index 00000000000..a9ba6d1dd2b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidenceCdrAux.hpp @@ -0,0 +1,83 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AltitudeConfidenceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCECDRAUX_HPP_ + +#include "AltitudeConfidence.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_AltitudeConfidence_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_AltitudeConfidence_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AltitudeConfidence& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidenceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidenceCdrAux.ipp new file mode 100644 index 00000000000..21c2b7556ab --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidenceCdrAux.ipp @@ -0,0 +1,163 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AltitudeConfidenceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCECDRAUX_IPP_ + +#include "AltitudeConfidenceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::AltitudeConfidence& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AltitudeConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::AltitudeConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AltitudeConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCECDRAUX_IPP_ + 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..f78d53f0838 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidencePubSubTypes.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 AltitudeConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "AltitudeConfidencePubSubTypes.h" +#include "AltitudeConfidenceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(AltitudeConfidence::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_AltitudeConfidence_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +AltitudeConfidencePubSubType::~AltitudeConfidencePubSubType() +{ +} + +bool AltitudeConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool AltitudeConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function AltitudeConfidencePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..603c4444696 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeConfidencePubSubTypes.h @@ -0,0 +1,169 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "AltitudeConfidence.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~AltitudeConfidencePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDECONFIDENCE_PUBSUBTYPES_H_ + 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..579a016a838 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudePubSubTypes.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 AltitudePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "AltitudePubSubTypes.h" +#include "AltitudeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +AltitudePubSubType::AltitudePubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::Altitude_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Altitude::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_Altitude_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +AltitudePubSubType::~AltitudePubSubType() +{ +} + +bool AltitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool AltitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function AltitudePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..5cd0c42a1b6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "Altitude.h" + +#include "AltitudeConfidencePubSubTypes.h" +#include "AltitudeValuePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~AltitudePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDE_PUBSUBTYPES_H_ + 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..0efb4697ac2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValue.cxx @@ -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 AltitudeValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace AltitudeValue_Constants { + + +} // namespace AltitudeValue_Constants + + +AltitudeValue::AltitudeValue() +{ +} + +AltitudeValue::~AltitudeValue() +{ +} + +AltitudeValue::AltitudeValue( + const AltitudeValue& x) +{ + m_value = x.m_value; +} + +AltitudeValue::AltitudeValue( + AltitudeValue&& x) noexcept +{ + m_value = x.m_value; +} + +AltitudeValue& AltitudeValue::operator =( + const AltitudeValue& x) +{ + + m_value = x.m_value; + return *this; +} + +AltitudeValue& AltitudeValue::operator =( + AltitudeValue&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool AltitudeValue::operator ==( + const AltitudeValue& x) const +{ + return (m_value == x.m_value); +} + +bool AltitudeValue::operator !=( + const AltitudeValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void AltitudeValue::value( + int32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int32_t AltitudeValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int32_t& AltitudeValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "AltitudeValueCdrAux.ipp" + 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..39d58febb62 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValue.h @@ -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 AltitudeValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int32_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValueCdrAux.hpp new file mode 100644 index 00000000000..6538d5cf498 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValueCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AltitudeValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUECDRAUX_HPP_ + +#include "AltitudeValue.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_AltitudeValue_max_cdr_typesize {8UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_AltitudeValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AltitudeValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValueCdrAux.ipp new file mode 100644 index 00000000000..e61d9247dd7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValueCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AltitudeValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUECDRAUX_IPP_ + +#include "AltitudeValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::AltitudeValue& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AltitudeValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::AltitudeValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::AltitudeValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUECDRAUX_IPP_ + 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..d861eddaabd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValuePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "AltitudeValuePubSubTypes.h" +#include "AltitudeValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(AltitudeValue::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_AltitudeValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +AltitudeValuePubSubType::~AltitudeValuePubSubType() +{ +} + +bool AltitudeValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool AltitudeValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function AltitudeValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..0b5fd497255 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/AltitudeValuePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "AltitudeValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~AltitudeValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ALTITUDEVALUE_PUBSUBTYPES_H_ + 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..6bc9d6a2ec9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainer.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 BasicContainer.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +BasicContainer::BasicContainer() +{ +} + +BasicContainer::~BasicContainer() +{ +} + +BasicContainer::BasicContainer( + const BasicContainer& x) +{ + m_station_type = x.m_station_type; + m_reference_position = x.m_reference_position; +} + +BasicContainer::BasicContainer( + BasicContainer&& x) noexcept +{ + m_station_type = std::move(x.m_station_type); + m_reference_position = std::move(x.m_reference_position); +} + +BasicContainer& BasicContainer::operator =( + const BasicContainer& x) +{ + + m_station_type = x.m_station_type; + m_reference_position = x.m_reference_position; + return *this; +} + +BasicContainer& BasicContainer::operator =( + BasicContainer&& x) noexcept +{ + + m_station_type = std::move(x.m_station_type); + m_reference_position = std::move(x.m_reference_position); + return *this; +} + +bool BasicContainer::operator ==( + const BasicContainer& x) const +{ + return (m_station_type == x.m_station_type && + m_reference_position == x.m_reference_position); +} + +bool BasicContainer::operator !=( + const BasicContainer& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member station_type + * @param _station_type New value to be copied in member station_type + */ +void 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 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& 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& 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 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 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& 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& BasicContainer::reference_position() +{ + return m_reference_position; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "BasicContainerCdrAux.ipp" + 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..4ae14db4e61 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainer.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ReferencePosition.h" +#include "StationType.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerCdrAux.hpp new file mode 100644 index 00000000000..6f703f5a250 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerCdrAux.hpp @@ -0,0 +1,59 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file BasicContainerCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINERCDRAUX_HPP_ + +#include "BasicContainer.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_BasicContainer_max_cdr_typesize {77UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_BasicContainer_max_key_cdr_typesize {0UL}; + + + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::BasicContainer& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerCdrAux.ipp new file mode 100644 index 00000000000..344bebfeb22 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file BasicContainerCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINERCDRAUX_IPP_ + +#include "BasicContainerCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::BasicContainer& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.station_type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.reference_position(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::BasicContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.station_type() + << eprosima::fastcdr::MemberId(1) << data.reference_position() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::BasicContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.station_type(); + break; + + case 1: + dcdr >> data.reference_position(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::BasicContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINERCDRAUX_IPP_ + 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..9070831aaa3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerPubSubTypes.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 BasicContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "BasicContainerPubSubTypes.h" +#include "BasicContainerCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +BasicContainerPubSubType::BasicContainerPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::BasicContainer_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(BasicContainer::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_BasicContainer_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +BasicContainerPubSubType::~BasicContainerPubSubType() +{ +} + +bool BasicContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool BasicContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function BasicContainerPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..331670d2373 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicContainerPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "BasicContainer.h" + +#include "ReferencePositionPubSubTypes.h" +#include "StationTypePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~BasicContainerPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICCONTAINER_PUBSUBTYPES_H_ + 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..f321cad4474 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.cxx @@ -0,0 +1,1039 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +BasicVehicleContainerHighFrequency::BasicVehicleContainerHighFrequency() +{ +} + +BasicVehicleContainerHighFrequency::~BasicVehicleContainerHighFrequency() +{ +} + +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; +} + +BasicVehicleContainerHighFrequency::BasicVehicleContainerHighFrequency( + BasicVehicleContainerHighFrequency&& x) noexcept +{ + 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; +} + +BasicVehicleContainerHighFrequency& 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; +} + +BasicVehicleContainerHighFrequency& BasicVehicleContainerHighFrequency::operator =( + BasicVehicleContainerHighFrequency&& x) noexcept +{ + + 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 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 BasicVehicleContainerHighFrequency::operator !=( + const BasicVehicleContainerHighFrequency& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member heading + * @param _heading New value to be copied in member heading + */ +void 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& BasicVehicleContainerHighFrequency::cen_dsrc_tolling_zone_is_present() +{ + return m_cen_dsrc_tolling_zone_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "BasicVehicleContainerHighFrequencyCdrAux.ipp" + 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..03387d831c6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequency.h @@ -0,0 +1,759 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCY_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCY_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#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" + + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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{false}; + etsi_its_cam_msgs::msg::LanePosition m_lane_position; + bool m_lane_position_is_present{false}; + etsi_its_cam_msgs::msg::SteeringWheelAngle m_steering_wheel_angle; + bool m_steering_wheel_angle_is_present{false}; + etsi_its_cam_msgs::msg::LateralAcceleration m_lateral_acceleration; + bool m_lateral_acceleration_is_present{false}; + etsi_its_cam_msgs::msg::VerticalAcceleration m_vertical_acceleration; + bool m_vertical_acceleration_is_present{false}; + etsi_its_cam_msgs::msg::PerformanceClass m_performance_class; + bool m_performance_class_is_present{false}; + etsi_its_cam_msgs::msg::CenDsrcTollingZone m_cen_dsrc_tolling_zone; + bool m_cen_dsrc_tolling_zone_is_present{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCY_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyCdrAux.hpp new file mode 100644 index 00000000000..7fdc325980f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyCdrAux.hpp @@ -0,0 +1,58 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file BasicVehicleContainerHighFrequencyCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCYCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCYCDRAUX_HPP_ + +#include "BasicVehicleContainerHighFrequency.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_BasicVehicleContainerHighFrequency_max_cdr_typesize {370UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_BasicVehicleContainerHighFrequency_max_key_cdr_typesize {0UL}; + + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCYCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyCdrAux.ipp new file mode 100644 index 00000000000..c8d783db9a0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyCdrAux.ipp @@ -0,0 +1,306 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file BasicVehicleContainerHighFrequencyCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCYCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCYCDRAUX_IPP_ + +#include "BasicVehicleContainerHighFrequencyCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.heading(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.speed(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.drive_direction(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.vehicle_length(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.vehicle_width(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.longitudinal_acceleration(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.curvature(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.curvature_calculation_mode(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.yaw_rate(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), + data.acceleration_control(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(10), + data.acceleration_control_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(11), + data.lane_position(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(12), + data.lane_position_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(13), + data.steering_wheel_angle(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(14), + data.steering_wheel_angle_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(15), + data.lateral_acceleration(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(16), + data.lateral_acceleration_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(17), + data.vertical_acceleration(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(18), + data.vertical_acceleration_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(19), + data.performance_class(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(20), + data.performance_class_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(21), + data.cen_dsrc_tolling_zone(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(22), + data.cen_dsrc_tolling_zone_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.heading() + << eprosima::fastcdr::MemberId(1) << data.speed() + << eprosima::fastcdr::MemberId(2) << data.drive_direction() + << eprosima::fastcdr::MemberId(3) << data.vehicle_length() + << eprosima::fastcdr::MemberId(4) << data.vehicle_width() + << eprosima::fastcdr::MemberId(5) << data.longitudinal_acceleration() + << eprosima::fastcdr::MemberId(6) << data.curvature() + << eprosima::fastcdr::MemberId(7) << data.curvature_calculation_mode() + << eprosima::fastcdr::MemberId(8) << data.yaw_rate() + << eprosima::fastcdr::MemberId(9) << data.acceleration_control() + << eprosima::fastcdr::MemberId(10) << data.acceleration_control_is_present() + << eprosima::fastcdr::MemberId(11) << data.lane_position() + << eprosima::fastcdr::MemberId(12) << data.lane_position_is_present() + << eprosima::fastcdr::MemberId(13) << data.steering_wheel_angle() + << eprosima::fastcdr::MemberId(14) << data.steering_wheel_angle_is_present() + << eprosima::fastcdr::MemberId(15) << data.lateral_acceleration() + << eprosima::fastcdr::MemberId(16) << data.lateral_acceleration_is_present() + << eprosima::fastcdr::MemberId(17) << data.vertical_acceleration() + << eprosima::fastcdr::MemberId(18) << data.vertical_acceleration_is_present() + << eprosima::fastcdr::MemberId(19) << data.performance_class() + << eprosima::fastcdr::MemberId(20) << data.performance_class_is_present() + << eprosima::fastcdr::MemberId(21) << data.cen_dsrc_tolling_zone() + << eprosima::fastcdr::MemberId(22) << data.cen_dsrc_tolling_zone_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.heading(); + break; + + case 1: + dcdr >> data.speed(); + break; + + case 2: + dcdr >> data.drive_direction(); + break; + + case 3: + dcdr >> data.vehicle_length(); + break; + + case 4: + dcdr >> data.vehicle_width(); + break; + + case 5: + dcdr >> data.longitudinal_acceleration(); + break; + + case 6: + dcdr >> data.curvature(); + break; + + case 7: + dcdr >> data.curvature_calculation_mode(); + break; + + case 8: + dcdr >> data.yaw_rate(); + break; + + case 9: + dcdr >> data.acceleration_control(); + break; + + case 10: + dcdr >> data.acceleration_control_is_present(); + break; + + case 11: + dcdr >> data.lane_position(); + break; + + case 12: + dcdr >> data.lane_position_is_present(); + break; + + case 13: + dcdr >> data.steering_wheel_angle(); + break; + + case 14: + dcdr >> data.steering_wheel_angle_is_present(); + break; + + case 15: + dcdr >> data.lateral_acceleration(); + break; + + case 16: + dcdr >> data.lateral_acceleration_is_present(); + break; + + case 17: + dcdr >> data.vertical_acceleration(); + break; + + case 18: + dcdr >> data.vertical_acceleration_is_present(); + break; + + case 19: + dcdr >> data.performance_class(); + break; + + case 20: + dcdr >> data.performance_class_is_present(); + break; + + case 21: + dcdr >> data.cen_dsrc_tolling_zone(); + break; + + case 22: + dcdr >> data.cen_dsrc_tolling_zone_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::BasicVehicleContainerHighFrequency& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCYCDRAUX_IPP_ + 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..94704f8949d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyPubSubTypes.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 BasicVehicleContainerHighFrequencyPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "BasicVehicleContainerHighFrequencyPubSubTypes.h" +#include "BasicVehicleContainerHighFrequencyCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +BasicVehicleContainerHighFrequencyPubSubType::BasicVehicleContainerHighFrequencyPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::BasicVehicleContainerHighFrequency_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(BasicVehicleContainerHighFrequency::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_BasicVehicleContainerHighFrequency_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +BasicVehicleContainerHighFrequencyPubSubType::~BasicVehicleContainerHighFrequencyPubSubType() +{ +} + +bool BasicVehicleContainerHighFrequencyPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool BasicVehicleContainerHighFrequencyPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function BasicVehicleContainerHighFrequencyPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..3d81ae1fe11 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerHighFrequencyPubSubTypes.h @@ -0,0 +1,151 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "BasicVehicleContainerHighFrequency.h" + +#include "DriveDirectionPubSubTypes.h" +#include "SpeedPubSubTypes.h" +#include "HeadingPubSubTypes.h" +#include "VehicleWidthPubSubTypes.h" +#include "CenDsrcTollingZonePubSubTypes.h" +#include "YawRatePubSubTypes.h" +#include "VehicleLengthPubSubTypes.h" +#include "CurvatureCalculationModePubSubTypes.h" +#include "LanePositionPubSubTypes.h" +#include "LateralAccelerationPubSubTypes.h" +#include "VerticalAccelerationPubSubTypes.h" +#include "SteeringWheelAnglePubSubTypes.h" +#include "LongitudinalAccelerationPubSubTypes.h" +#include "CurvaturePubSubTypes.h" +#include "PerformanceClassPubSubTypes.h" +#include "AccelerationControlPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~BasicVehicleContainerHighFrequencyPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERHIGHFREQUENCY_PUBSUBTYPES_H_ + 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..d9fd66f1dcf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.cxx @@ -0,0 +1,229 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +BasicVehicleContainerLowFrequency::BasicVehicleContainerLowFrequency() +{ +} + +BasicVehicleContainerLowFrequency::~BasicVehicleContainerLowFrequency() +{ +} + +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; +} + +BasicVehicleContainerLowFrequency::BasicVehicleContainerLowFrequency( + BasicVehicleContainerLowFrequency&& x) noexcept +{ + 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); +} + +BasicVehicleContainerLowFrequency& 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; +} + +BasicVehicleContainerLowFrequency& BasicVehicleContainerLowFrequency::operator =( + BasicVehicleContainerLowFrequency&& x) noexcept +{ + + 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 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 BasicVehicleContainerLowFrequency::operator !=( + const BasicVehicleContainerLowFrequency& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member vehicle_role + * @param _vehicle_role New value to be copied in member vehicle_role + */ +void 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 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& 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& 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 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 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& 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& 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 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 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& 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& BasicVehicleContainerLowFrequency::path_history() +{ + return m_path_history; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "BasicVehicleContainerLowFrequencyCdrAux.ipp" + 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..194c838ebe7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequency.h @@ -0,0 +1,235 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCY_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCY_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "VehicleRole.h" +#include "ExteriorLights.h" +#include "PathHistory.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyCdrAux.hpp new file mode 100644 index 00000000000..642da0f6ff2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file BasicVehicleContainerLowFrequencyCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCYCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCYCDRAUX_HPP_ + +#include "BasicVehicleContainerLowFrequency.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_BasicVehicleContainerLowFrequency_max_cdr_typesize {4135UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_BasicVehicleContainerLowFrequency_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCYCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyCdrAux.ipp new file mode 100644 index 00000000000..498fa1e942b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file BasicVehicleContainerLowFrequencyCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCYCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCYCDRAUX_IPP_ + +#include "BasicVehicleContainerLowFrequencyCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.vehicle_role(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.exterior_lights(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.path_history(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.vehicle_role() + << eprosima::fastcdr::MemberId(1) << data.exterior_lights() + << eprosima::fastcdr::MemberId(2) << data.path_history() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.vehicle_role(); + break; + + case 1: + dcdr >> data.exterior_lights(); + break; + + case 2: + dcdr >> data.path_history(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::BasicVehicleContainerLowFrequency& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCYCDRAUX_IPP_ + 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..1a3862b36b3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyPubSubTypes.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 BasicVehicleContainerLowFrequencyPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "BasicVehicleContainerLowFrequencyPubSubTypes.h" +#include "BasicVehicleContainerLowFrequencyCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +BasicVehicleContainerLowFrequencyPubSubType::BasicVehicleContainerLowFrequencyPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::BasicVehicleContainerLowFrequency_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(BasicVehicleContainerLowFrequency::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_BasicVehicleContainerLowFrequency_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +BasicVehicleContainerLowFrequencyPubSubType::~BasicVehicleContainerLowFrequencyPubSubType() +{ +} + +bool BasicVehicleContainerLowFrequencyPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool BasicVehicleContainerLowFrequencyPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function BasicVehicleContainerLowFrequencyPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..4a8b23018f0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/BasicVehicleContainerLowFrequencyPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "BasicVehicleContainerLowFrequency.h" + +#include "VehicleRolePubSubTypes.h" +#include "ExteriorLightsPubSubTypes.h" +#include "PathHistoryPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~BasicVehicleContainerLowFrequencyPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_BASICVEHICLECONTAINERLOWFREQUENCY_PUBSUBTYPES_H_ + 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..75b5d56c8e8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAM.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 CAM.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +CAM::CAM() +{ +} + +CAM::~CAM() +{ +} + +CAM::CAM( + const CAM& x) +{ + m_header = x.m_header; + m_cam = x.m_cam; +} + +CAM::CAM( + CAM&& x) noexcept +{ + m_header = std::move(x.m_header); + m_cam = std::move(x.m_cam); +} + +CAM& CAM::operator =( + const CAM& x) +{ + + m_header = x.m_header; + m_cam = x.m_cam; + return *this; +} + +CAM& CAM::operator =( + CAM&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_cam = std::move(x.m_cam); + return *this; +} + +bool CAM::operator ==( + const CAM& x) const +{ + return (m_header == x.m_header && + m_cam == x.m_cam); +} + +bool CAM::operator !=( + const CAM& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& 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& 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 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 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& 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& CAM::cam() +{ + return m_cam; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CAMCdrAux.ipp" + 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..c17c95f37e5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAM.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAM_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAM_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ItsPduHeader.h" +#include "CoopAwareness.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMCdrAux.hpp new file mode 100644 index 00000000000..a6fa50d753e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMCdrAux.hpp @@ -0,0 +1,120 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CAMCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMCDRAUX_HPP_ + +#include "CAM.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_CAM_max_cdr_typesize {12211UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_CAM_max_key_cdr_typesize {0UL}; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CAM& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMCdrAux.ipp new file mode 100644 index 00000000000..476b3298359 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CAMCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMCDRAUX_IPP_ + +#include "CAMCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::CAM& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.cam(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CAM& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.cam() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::CAM& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.cam(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CAM& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.cxx new file mode 100644 index 00000000000..1c4b7ebc843 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.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 CAMPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CAMPubSubTypes.h" +#include "CAMCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +CAMPubSubType::CAMPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::CAM_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CAM::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_CAM_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CAMPubSubType::~CAMPubSubType() +{ +} + +bool CAMPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CAM* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CAMPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + CAM* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CAMPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CAMPubSubType::createData() +{ + return reinterpret_cast(new CAM()); +} + +void CAMPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CAMPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace etsi_its_cam_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.h new file mode 100644 index 00000000000..65445205b31 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CAMPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CAMPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "CAM.h" + +#include "ItsPduHeaderPubSubTypes.h" +#include "CoopAwarenessPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CAM 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 CAM defined by the user in the IDL file. + * @ingroup CAM + */ +class CAMPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CAM type; + + eProsima_user_DllExport CAMPubSubType(); + + eProsima_user_DllExport ~CAMPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAM_PUBSUBTYPES_H_ + 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..b894150fe08 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParameters.cxx @@ -0,0 +1,341 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +CamParameters::CamParameters() +{ +} + +CamParameters::~CamParameters() +{ +} + +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; +} + +CamParameters::CamParameters( + CamParameters&& x) noexcept +{ + 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; +} + +CamParameters& 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; +} + +CamParameters& CamParameters::operator =( + CamParameters&& x) noexcept +{ + + 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 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 CamParameters::operator !=( + const CamParameters& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member basic_container + * @param _basic_container New value to be copied in member basic_container + */ +void 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& CamParameters::special_vehicle_container_is_present() +{ + return m_special_vehicle_container_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CamParametersCdrAux.ipp" + 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..edd3675cbde --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParameters.h @@ -0,0 +1,306 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERS_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "SpecialVehicleContainer.h" +#include "BasicContainer.h" +#include "HighFrequencyContainer.h" +#include "LowFrequencyContainer.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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{false}; + etsi_its_cam_msgs::msg::SpecialVehicleContainer m_special_vehicle_container; + bool m_special_vehicle_container_is_present{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersCdrAux.hpp new file mode 100644 index 00000000000..30c52d14911 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CamParametersCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERSCDRAUX_HPP_ + +#include "CamParameters.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_CamParameters_max_cdr_typesize {12179UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_CamParameters_max_key_cdr_typesize {0UL}; + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CamParameters& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersCdrAux.ipp new file mode 100644 index 00000000000..313e2d68978 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersCdrAux.ipp @@ -0,0 +1,170 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CamParametersCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERSCDRAUX_IPP_ + +#include "CamParametersCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::CamParameters& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.basic_container(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.high_frequency_container(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.low_frequency_container(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.low_frequency_container_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.special_vehicle_container(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.special_vehicle_container_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CamParameters& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.basic_container() + << eprosima::fastcdr::MemberId(1) << data.high_frequency_container() + << eprosima::fastcdr::MemberId(2) << data.low_frequency_container() + << eprosima::fastcdr::MemberId(3) << data.low_frequency_container_is_present() + << eprosima::fastcdr::MemberId(4) << data.special_vehicle_container() + << eprosima::fastcdr::MemberId(5) << data.special_vehicle_container_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::CamParameters& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.basic_container(); + break; + + case 1: + dcdr >> data.high_frequency_container(); + break; + + case 2: + dcdr >> data.low_frequency_container(); + break; + + case 3: + dcdr >> data.low_frequency_container_is_present(); + break; + + case 4: + dcdr >> data.special_vehicle_container(); + break; + + case 5: + dcdr >> data.special_vehicle_container_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CamParameters& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERSCDRAUX_IPP_ + 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..6f2d24a7f06 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersPubSubTypes.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 CamParametersPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CamParametersPubSubTypes.h" +#include "CamParametersCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +CamParametersPubSubType::CamParametersPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::CamParameters_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CamParameters::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_CamParameters_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CamParametersPubSubType::~CamParametersPubSubType() +{ +} + +bool CamParametersPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CamParametersPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CamParametersPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..918dadfcc80 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CamParametersPubSubTypes.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 CamParametersPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "CamParameters.h" + +#include "SpecialVehicleContainerPubSubTypes.h" +#include "BasicContainerPubSubTypes.h" +#include "HighFrequencyContainerPubSubTypes.h" +#include "LowFrequencyContainerPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CamParametersPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAMPARAMETERS_PUBSUBTYPES_H_ + 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..62f6d47272b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCode.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 CauseCode.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +CauseCode::CauseCode() +{ +} + +CauseCode::~CauseCode() +{ +} + +CauseCode::CauseCode( + const CauseCode& x) +{ + m_cause_code = x.m_cause_code; + m_sub_cause_code = x.m_sub_cause_code; +} + +CauseCode::CauseCode( + CauseCode&& x) noexcept +{ + m_cause_code = std::move(x.m_cause_code); + m_sub_cause_code = std::move(x.m_sub_cause_code); +} + +CauseCode& CauseCode::operator =( + const CauseCode& x) +{ + + m_cause_code = x.m_cause_code; + m_sub_cause_code = x.m_sub_cause_code; + return *this; +} + +CauseCode& CauseCode::operator =( + CauseCode&& x) noexcept +{ + + m_cause_code = std::move(x.m_cause_code); + m_sub_cause_code = std::move(x.m_sub_cause_code); + return *this; +} + +bool CauseCode::operator ==( + const CauseCode& x) const +{ + return (m_cause_code == x.m_cause_code && + m_sub_cause_code == x.m_sub_cause_code); +} + +bool CauseCode::operator !=( + const CauseCode& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member cause_code + * @param _cause_code New value to be copied in member cause_code + */ +void 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 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& 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& 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 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 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& 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& CauseCode::sub_cause_code() +{ + return m_sub_cause_code; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CauseCodeCdrAux.ipp" + 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..0ddae061ddd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCode.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "SubCauseCodeType.h" +#include "CauseCodeType.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeCdrAux.hpp new file mode 100644 index 00000000000..a94940d7b2e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CauseCodeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODECDRAUX_HPP_ + +#include "CauseCode.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_CauseCode_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_CauseCode_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CauseCode& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeCdrAux.ipp new file mode 100644 index 00000000000..4f3652bccf4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CauseCodeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODECDRAUX_IPP_ + +#include "CauseCodeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::CauseCode& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.cause_code(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.sub_cause_code(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CauseCode& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.cause_code() + << eprosima::fastcdr::MemberId(1) << data.sub_cause_code() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::CauseCode& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.cause_code(); + break; + + case 1: + dcdr >> data.sub_cause_code(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CauseCode& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODECDRAUX_IPP_ + 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..8307597a139 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodePubSubTypes.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 CauseCodePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CauseCodePubSubTypes.h" +#include "CauseCodeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +CauseCodePubSubType::CauseCodePubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::CauseCode_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CauseCode::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_CauseCode_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CauseCodePubSubType::~CauseCodePubSubType() +{ +} + +bool CauseCodePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CauseCodePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CauseCodePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace etsi_its_cam_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodePubSubTypes.h new file mode 100644 index 00000000000..3e47af41d22 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "CauseCode.h" + +#include "SubCauseCodeTypePubSubTypes.h" +#include "CauseCodeTypePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CauseCode 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 CauseCode defined by the user in the IDL file. + * @ingroup CauseCode + */ +class CauseCodePubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CauseCode type; + + eProsima_user_DllExport CauseCodePubSubType(); + + eProsima_user_DllExport ~CauseCodePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODE_PUBSUBTYPES_H_ + 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..2caebcbe85f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeType.cxx @@ -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 CauseCodeType.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace CauseCodeType_Constants { + + +} // namespace CauseCodeType_Constants + + +CauseCodeType::CauseCodeType() +{ +} + +CauseCodeType::~CauseCodeType() +{ +} + +CauseCodeType::CauseCodeType( + const CauseCodeType& x) +{ + m_value = x.m_value; +} + +CauseCodeType::CauseCodeType( + CauseCodeType&& x) noexcept +{ + m_value = x.m_value; +} + +CauseCodeType& CauseCodeType::operator =( + const CauseCodeType& x) +{ + + m_value = x.m_value; + return *this; +} + +CauseCodeType& CauseCodeType::operator =( + CauseCodeType&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool CauseCodeType::operator ==( + const CauseCodeType& x) const +{ + return (m_value == x.m_value); +} + +bool CauseCodeType::operator !=( + const CauseCodeType& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void CauseCodeType::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t CauseCodeType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& CauseCodeType::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CauseCodeTypeCdrAux.ipp" + 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..687946855a5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeType.h @@ -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 CauseCodeType.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypeCdrAux.hpp new file mode 100644 index 00000000000..5993fb57d6c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypeCdrAux.hpp @@ -0,0 +1,109 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CauseCodeTypeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPECDRAUX_HPP_ + +#include "CauseCodeType.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_CauseCodeType_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_CauseCodeType_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CauseCodeType& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypeCdrAux.ipp new file mode 100644 index 00000000000..4f93299f109 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypeCdrAux.ipp @@ -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 CauseCodeTypeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPECDRAUX_IPP_ + +#include "CauseCodeTypeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::CauseCodeType& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CauseCodeType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::CauseCodeType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CauseCodeType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPECDRAUX_IPP_ + 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..b39ec50290d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypePubSubTypes.cxx @@ -0,0 +1,260 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CauseCodeTypePubSubTypes.h" +#include "CauseCodeTypeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CauseCodeType::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_CauseCodeType_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CauseCodeTypePubSubType::~CauseCodeTypePubSubType() +{ +} + +bool CauseCodeTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CauseCodeTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CauseCodeTypePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..8578de6fd24 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CauseCodeTypePubSubTypes.h @@ -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 CauseCodeTypePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "CauseCodeType.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~CauseCodeTypePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CAUSECODETYPE_PUBSUBTYPES_H_ + 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..fa355fdfa30 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZone.cxx @@ -0,0 +1,263 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +CenDsrcTollingZone::CenDsrcTollingZone() +{ +} + +CenDsrcTollingZone::~CenDsrcTollingZone() +{ +} + +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; +} + +CenDsrcTollingZone::CenDsrcTollingZone( + CenDsrcTollingZone&& x) noexcept +{ + 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; +} + +CenDsrcTollingZone& 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; +} + +CenDsrcTollingZone& CenDsrcTollingZone::operator =( + CenDsrcTollingZone&& x) noexcept +{ + + 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 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 CenDsrcTollingZone::operator !=( + const CenDsrcTollingZone& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& CenDsrcTollingZone::cen_dsrc_tolling_zone_id_is_present() +{ + return m_cen_dsrc_tolling_zone_id_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CenDsrcTollingZoneCdrAux.ipp" + 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..8522b109bab --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZone.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 CenDsrcTollingZone.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CenDsrcTollingZoneID.h" +#include "Latitude.h" +#include "Longitude.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneCdrAux.hpp new file mode 100644 index 00000000000..ea8d870734c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CenDsrcTollingZoneCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONECDRAUX_HPP_ + +#include "CenDsrcTollingZone.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_CenDsrcTollingZone_max_cdr_typesize {33UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_CenDsrcTollingZone_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CenDsrcTollingZone& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneCdrAux.ipp new file mode 100644 index 00000000000..5fe39652033 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneCdrAux.ipp @@ -0,0 +1,154 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CenDsrcTollingZoneCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONECDRAUX_IPP_ + +#include "CenDsrcTollingZoneCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::CenDsrcTollingZone& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.protected_zone_latitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.protected_zone_longitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.cen_dsrc_tolling_zone_id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.cen_dsrc_tolling_zone_id_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CenDsrcTollingZone& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.protected_zone_latitude() + << eprosima::fastcdr::MemberId(1) << data.protected_zone_longitude() + << eprosima::fastcdr::MemberId(2) << data.cen_dsrc_tolling_zone_id() + << eprosima::fastcdr::MemberId(3) << data.cen_dsrc_tolling_zone_id_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::CenDsrcTollingZone& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.protected_zone_latitude(); + break; + + case 1: + dcdr >> data.protected_zone_longitude(); + break; + + case 2: + dcdr >> data.cen_dsrc_tolling_zone_id(); + break; + + case 3: + dcdr >> data.cen_dsrc_tolling_zone_id_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CenDsrcTollingZone& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONECDRAUX_IPP_ + 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..9ab5a24b0af --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.cxx @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +CenDsrcTollingZoneID::CenDsrcTollingZoneID() +{ +} + +CenDsrcTollingZoneID::~CenDsrcTollingZoneID() +{ +} + +CenDsrcTollingZoneID::CenDsrcTollingZoneID( + const CenDsrcTollingZoneID& x) +{ + m_value = x.m_value; +} + +CenDsrcTollingZoneID::CenDsrcTollingZoneID( + CenDsrcTollingZoneID&& x) noexcept +{ + m_value = std::move(x.m_value); +} + +CenDsrcTollingZoneID& CenDsrcTollingZoneID::operator =( + const CenDsrcTollingZoneID& x) +{ + + m_value = x.m_value; + return *this; +} + +CenDsrcTollingZoneID& CenDsrcTollingZoneID::operator =( + CenDsrcTollingZoneID&& x) noexcept +{ + + m_value = std::move(x.m_value); + return *this; +} + +bool CenDsrcTollingZoneID::operator ==( + const CenDsrcTollingZoneID& x) const +{ + return (m_value == x.m_value); +} + +bool CenDsrcTollingZoneID::operator !=( + const CenDsrcTollingZoneID& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void 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 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& 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& CenDsrcTollingZoneID::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CenDsrcTollingZoneIDCdrAux.ipp" + 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..6d5a4628fcd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneID.h @@ -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 CenDsrcTollingZoneID.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEID_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEID_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ProtectedZoneID.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDCdrAux.hpp new file mode 100644 index 00000000000..30c70d33804 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CenDsrcTollingZoneIDCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEIDCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEIDCDRAUX_HPP_ + +#include "CenDsrcTollingZoneID.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_CenDsrcTollingZoneID_max_cdr_typesize {12UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_CenDsrcTollingZoneID_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEIDCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDCdrAux.ipp new file mode 100644 index 00000000000..bde7caca3d1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDCdrAux.ipp @@ -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 CenDsrcTollingZoneIDCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEIDCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEIDCDRAUX_IPP_ + +#include "CenDsrcTollingZoneIDCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CenDsrcTollingZoneID& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEIDCDRAUX_IPP_ + 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..f3b3413f3f4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDPubSubTypes.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 CenDsrcTollingZoneIDPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CenDsrcTollingZoneIDPubSubTypes.h" +#include "CenDsrcTollingZoneIDCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +CenDsrcTollingZoneIDPubSubType::CenDsrcTollingZoneIDPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::CenDsrcTollingZoneID_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CenDsrcTollingZoneID::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_CenDsrcTollingZoneID_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CenDsrcTollingZoneIDPubSubType::~CenDsrcTollingZoneIDPubSubType() +{ +} + +bool CenDsrcTollingZoneIDPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CenDsrcTollingZoneIDPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CenDsrcTollingZoneIDPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..af2032422ad --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZoneIDPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "CenDsrcTollingZoneID.h" + +#include "ProtectedZoneIDPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CenDsrcTollingZoneIDPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONEID_PUBSUBTYPES_H_ + 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..bb47de18d6e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZonePubSubTypes.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 CenDsrcTollingZonePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CenDsrcTollingZonePubSubTypes.h" +#include "CenDsrcTollingZoneCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +CenDsrcTollingZonePubSubType::CenDsrcTollingZonePubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::CenDsrcTollingZone_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CenDsrcTollingZone::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_CenDsrcTollingZone_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CenDsrcTollingZonePubSubType::~CenDsrcTollingZonePubSubType() +{ +} + +bool CenDsrcTollingZonePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CenDsrcTollingZonePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CenDsrcTollingZonePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..3a4d49e2b3f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CenDsrcTollingZonePubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "CenDsrcTollingZone.h" + +#include "CenDsrcTollingZoneIDPubSubTypes.h" +#include "LatitudePubSubTypes.h" +#include "LongitudePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CenDsrcTollingZonePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CENDSRCTOLLINGZONE_PUBSUBTYPES_H_ + 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..d6d8bcd174d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanes.cxx @@ -0,0 +1,331 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +ClosedLanes::ClosedLanes() +{ +} + +ClosedLanes::~ClosedLanes() +{ +} + +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; +} + +ClosedLanes::ClosedLanes( + ClosedLanes&& x) noexcept +{ + 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; +} + +ClosedLanes& 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; +} + +ClosedLanes& ClosedLanes::operator =( + ClosedLanes&& x) noexcept +{ + + 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 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 ClosedLanes::operator !=( + const ClosedLanes& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& ClosedLanes::driving_lane_status_is_present() +{ + return m_driving_lane_status_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ClosedLanesCdrAux.ipp" + 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..a7055d970a7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanes.h @@ -0,0 +1,297 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANES_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANES_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "HardShoulderStatus.h" +#include "DrivingLaneStatus.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + etsi_its_cam_msgs::msg::HardShoulderStatus m_innerhard_shoulder_status; + bool m_innerhard_shoulder_status_is_present{false}; + etsi_its_cam_msgs::msg::HardShoulderStatus m_outerhard_shoulder_status; + bool m_outerhard_shoulder_status_is_present{false}; + etsi_its_cam_msgs::msg::DrivingLaneStatus m_driving_lane_status; + bool m_driving_lane_status_is_present{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANES_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesCdrAux.hpp new file mode 100644 index 00000000000..96c8ad85cdf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ClosedLanesCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANESCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANESCDRAUX_HPP_ + +#include "ClosedLanes.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_ClosedLanes_max_cdr_typesize {130UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_ClosedLanes_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ClosedLanes& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANESCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesCdrAux.ipp new file mode 100644 index 00000000000..9aae0557c7c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesCdrAux.ipp @@ -0,0 +1,170 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ClosedLanesCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANESCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANESCDRAUX_IPP_ + +#include "ClosedLanesCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::ClosedLanes& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.innerhard_shoulder_status(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.innerhard_shoulder_status_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.outerhard_shoulder_status(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.outerhard_shoulder_status_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.driving_lane_status(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.driving_lane_status_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ClosedLanes& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.innerhard_shoulder_status() + << eprosima::fastcdr::MemberId(1) << data.innerhard_shoulder_status_is_present() + << eprosima::fastcdr::MemberId(2) << data.outerhard_shoulder_status() + << eprosima::fastcdr::MemberId(3) << data.outerhard_shoulder_status_is_present() + << eprosima::fastcdr::MemberId(4) << data.driving_lane_status() + << eprosima::fastcdr::MemberId(5) << data.driving_lane_status_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::ClosedLanes& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.innerhard_shoulder_status(); + break; + + case 1: + dcdr >> data.innerhard_shoulder_status_is_present(); + break; + + case 2: + dcdr >> data.outerhard_shoulder_status(); + break; + + case 3: + dcdr >> data.outerhard_shoulder_status_is_present(); + break; + + case 4: + dcdr >> data.driving_lane_status(); + break; + + case 5: + dcdr >> data.driving_lane_status_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ClosedLanes& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANESCDRAUX_IPP_ + 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..b73f5399f40 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesPubSubTypes.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 ClosedLanesPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ClosedLanesPubSubTypes.h" +#include "ClosedLanesCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +ClosedLanesPubSubType::ClosedLanesPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::ClosedLanes_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ClosedLanes::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_ClosedLanes_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ClosedLanesPubSubType::~ClosedLanesPubSubType() +{ +} + +bool ClosedLanesPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ClosedLanesPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ClosedLanesPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace etsi_its_cam_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesPubSubTypes.h new file mode 100644 index 00000000000..12787989a4b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ClosedLanesPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ClosedLanes.h" + +#include "HardShoulderStatusPubSubTypes.h" +#include "DrivingLaneStatusPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated ClosedLanes 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 ClosedLanes defined by the user in the IDL file. + * @ingroup ClosedLanes + */ +class ClosedLanesPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef ClosedLanes type; + + eProsima_user_DllExport ClosedLanesPubSubType(); + + eProsima_user_DllExport ~ClosedLanesPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CLOSEDLANES_PUBSUBTYPES_H_ + 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..f42a1661488 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwareness.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 CoopAwareness.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +CoopAwareness::CoopAwareness() +{ +} + +CoopAwareness::~CoopAwareness() +{ +} + +CoopAwareness::CoopAwareness( + const CoopAwareness& x) +{ + m_generation_delta_time = x.m_generation_delta_time; + m_cam_parameters = x.m_cam_parameters; +} + +CoopAwareness::CoopAwareness( + CoopAwareness&& x) noexcept +{ + m_generation_delta_time = std::move(x.m_generation_delta_time); + m_cam_parameters = std::move(x.m_cam_parameters); +} + +CoopAwareness& CoopAwareness::operator =( + const CoopAwareness& x) +{ + + m_generation_delta_time = x.m_generation_delta_time; + m_cam_parameters = x.m_cam_parameters; + return *this; +} + +CoopAwareness& CoopAwareness::operator =( + CoopAwareness&& x) noexcept +{ + + m_generation_delta_time = std::move(x.m_generation_delta_time); + m_cam_parameters = std::move(x.m_cam_parameters); + return *this; +} + +bool CoopAwareness::operator ==( + const CoopAwareness& x) const +{ + return (m_generation_delta_time == x.m_generation_delta_time && + m_cam_parameters == x.m_cam_parameters); +} + +bool CoopAwareness::operator !=( + const CoopAwareness& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& CoopAwareness::cam_parameters() +{ + return m_cam_parameters; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CoopAwarenessCdrAux.ipp" + 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..64e32d593fa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwareness.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESS_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESS_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "GenerationDeltaTime.h" +#include "CamParameters.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessCdrAux.hpp new file mode 100644 index 00000000000..430900d927c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessCdrAux.hpp @@ -0,0 +1,78 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CoopAwarenessCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESSCDRAUX_HPP_ + +#include "CoopAwareness.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_CoopAwareness_max_cdr_typesize {12195UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_CoopAwareness_max_key_cdr_typesize {0UL}; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CoopAwareness& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessCdrAux.ipp new file mode 100644 index 00000000000..e27ab5c4639 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CoopAwarenessCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESSCDRAUX_IPP_ + +#include "CoopAwarenessCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::CoopAwareness& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.generation_delta_time(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.cam_parameters(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CoopAwareness& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.generation_delta_time() + << eprosima::fastcdr::MemberId(1) << data.cam_parameters() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::CoopAwareness& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.generation_delta_time(); + break; + + case 1: + dcdr >> data.cam_parameters(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CoopAwareness& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESSCDRAUX_IPP_ + 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..93312e44b11 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessPubSubTypes.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 CoopAwarenessPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CoopAwarenessPubSubTypes.h" +#include "CoopAwarenessCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +CoopAwarenessPubSubType::CoopAwarenessPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::CoopAwareness_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CoopAwareness::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_CoopAwareness_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CoopAwarenessPubSubType::~CoopAwarenessPubSubType() +{ +} + +bool CoopAwarenessPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CoopAwarenessPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CoopAwarenessPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace etsi_its_cam_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessPubSubTypes.h new file mode 100644 index 00000000000..6b8740514e7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CoopAwarenessPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "CoopAwareness.h" + +#include "GenerationDeltaTimePubSubTypes.h" +#include "CamParametersPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated CoopAwareness 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 CoopAwareness defined by the user in the IDL file. + * @ingroup CoopAwareness + */ +class CoopAwarenessPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef CoopAwareness type; + + eProsima_user_DllExport CoopAwarenessPubSubType(); + + eProsima_user_DllExport ~CoopAwarenessPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_COOPAWARENESS_PUBSUBTYPES_H_ + 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..f0eeba37f52 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Curvature.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 Curvature.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +Curvature::Curvature() +{ +} + +Curvature::~Curvature() +{ +} + +Curvature::Curvature( + const Curvature& x) +{ + m_curvature_value = x.m_curvature_value; + m_curvature_confidence = x.m_curvature_confidence; +} + +Curvature::Curvature( + Curvature&& x) noexcept +{ + m_curvature_value = std::move(x.m_curvature_value); + m_curvature_confidence = std::move(x.m_curvature_confidence); +} + +Curvature& Curvature::operator =( + const Curvature& x) +{ + + m_curvature_value = x.m_curvature_value; + m_curvature_confidence = x.m_curvature_confidence; + return *this; +} + +Curvature& Curvature::operator =( + Curvature&& x) noexcept +{ + + m_curvature_value = std::move(x.m_curvature_value); + m_curvature_confidence = std::move(x.m_curvature_confidence); + return *this; +} + +bool Curvature::operator ==( + const Curvature& x) const +{ + return (m_curvature_value == x.m_curvature_value && + m_curvature_confidence == x.m_curvature_confidence); +} + +bool Curvature::operator !=( + const Curvature& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member curvature_value + * @param _curvature_value New value to be copied in member curvature_value + */ +void 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 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& 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& 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 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 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& 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& Curvature::curvature_confidence() +{ + return m_curvature_confidence; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CurvatureCdrAux.ipp" + 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..c6f485d5db2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Curvature.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CurvatureConfidence.h" +#include "CurvatureValue.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + 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..beb07285d9b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationMode.cxx @@ -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 CurvatureCalculationMode.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace CurvatureCalculationMode_Constants { + + +} // namespace CurvatureCalculationMode_Constants + + +CurvatureCalculationMode::CurvatureCalculationMode() +{ +} + +CurvatureCalculationMode::~CurvatureCalculationMode() +{ +} + +CurvatureCalculationMode::CurvatureCalculationMode( + const CurvatureCalculationMode& x) +{ + m_value = x.m_value; +} + +CurvatureCalculationMode::CurvatureCalculationMode( + CurvatureCalculationMode&& x) noexcept +{ + m_value = x.m_value; +} + +CurvatureCalculationMode& CurvatureCalculationMode::operator =( + const CurvatureCalculationMode& x) +{ + + m_value = x.m_value; + return *this; +} + +CurvatureCalculationMode& CurvatureCalculationMode::operator =( + CurvatureCalculationMode&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool CurvatureCalculationMode::operator ==( + const CurvatureCalculationMode& x) const +{ + return (m_value == x.m_value); +} + +bool CurvatureCalculationMode::operator !=( + const CurvatureCalculationMode& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void CurvatureCalculationMode::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t CurvatureCalculationMode::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& CurvatureCalculationMode::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CurvatureCalculationModeCdrAux.ipp" + 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..6c1d17931e0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationMode.h @@ -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 CurvatureCalculationMode.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModeCdrAux.hpp new file mode 100644 index 00000000000..caee00cb519 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModeCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CurvatureCalculationModeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODECDRAUX_HPP_ + +#include "CurvatureCalculationMode.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_CurvatureCalculationMode_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_CurvatureCalculationMode_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CurvatureCalculationMode& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModeCdrAux.ipp new file mode 100644 index 00000000000..dd604d3a4db --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModeCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CurvatureCalculationModeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODECDRAUX_IPP_ + +#include "CurvatureCalculationModeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::CurvatureCalculationMode& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CurvatureCalculationMode& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::CurvatureCalculationMode& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CurvatureCalculationMode& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODECDRAUX_IPP_ + 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..ded29f8ef88 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModePubSubTypes.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 CurvatureCalculationModePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CurvatureCalculationModePubSubTypes.h" +#include "CurvatureCalculationModeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CurvatureCalculationMode::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_CurvatureCalculationMode_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CurvatureCalculationModePubSubType::~CurvatureCalculationModePubSubType() +{ +} + +bool CurvatureCalculationModePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CurvatureCalculationModePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CurvatureCalculationModePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..d9c7ff6e175 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCalculationModePubSubTypes.h @@ -0,0 +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 CurvatureCalculationModePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "CurvatureCalculationMode.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + +} // 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 ~CurvatureCalculationModePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECALCULATIONMODE_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCdrAux.hpp new file mode 100644 index 00000000000..536d2e89522 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CurvatureCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECDRAUX_HPP_ + +#include "Curvature.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_Curvature_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_Curvature_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Curvature& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCdrAux.ipp new file mode 100644 index 00000000000..e8cb5905aaa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CurvatureCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECDRAUX_IPP_ + +#include "CurvatureCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::Curvature& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.curvature_value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.curvature_confidence(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Curvature& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.curvature_value() + << eprosima::fastcdr::MemberId(1) << data.curvature_confidence() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::Curvature& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.curvature_value(); + break; + + case 1: + dcdr >> data.curvature_confidence(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Curvature& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECDRAUX_IPP_ + 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..f8c67145fbb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidence.cxx @@ -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 CurvatureConfidence.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace CurvatureConfidence_Constants { + + +} // namespace CurvatureConfidence_Constants + + +CurvatureConfidence::CurvatureConfidence() +{ +} + +CurvatureConfidence::~CurvatureConfidence() +{ +} + +CurvatureConfidence::CurvatureConfidence( + const CurvatureConfidence& x) +{ + m_value = x.m_value; +} + +CurvatureConfidence::CurvatureConfidence( + CurvatureConfidence&& x) noexcept +{ + m_value = x.m_value; +} + +CurvatureConfidence& CurvatureConfidence::operator =( + const CurvatureConfidence& x) +{ + + m_value = x.m_value; + return *this; +} + +CurvatureConfidence& CurvatureConfidence::operator =( + CurvatureConfidence&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool CurvatureConfidence::operator ==( + const CurvatureConfidence& x) const +{ + return (m_value == x.m_value); +} + +bool CurvatureConfidence::operator !=( + const CurvatureConfidence& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void CurvatureConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t CurvatureConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& CurvatureConfidence::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CurvatureConfidenceCdrAux.ipp" + 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..985dc23dfb9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidence.h @@ -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 CurvatureConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidenceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidenceCdrAux.hpp new file mode 100644 index 00000000000..157287f5f62 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidenceCdrAux.hpp @@ -0,0 +1,67 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CurvatureConfidenceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCECDRAUX_HPP_ + +#include "CurvatureConfidence.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_CurvatureConfidence_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_CurvatureConfidence_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CurvatureConfidence& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidenceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidenceCdrAux.ipp new file mode 100644 index 00000000000..b97c5767dd6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidenceCdrAux.ipp @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CurvatureConfidenceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCECDRAUX_IPP_ + +#include "CurvatureConfidenceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::CurvatureConfidence& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CurvatureConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::CurvatureConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CurvatureConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCECDRAUX_IPP_ + 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..efebc9290c1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidencePubSubTypes.cxx @@ -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 CurvatureConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CurvatureConfidencePubSubTypes.h" +#include "CurvatureConfidenceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CurvatureConfidence::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_CurvatureConfidence_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CurvatureConfidencePubSubType::~CurvatureConfidencePubSubType() +{ +} + +bool CurvatureConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CurvatureConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CurvatureConfidencePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..091e397ce16 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureConfidencePubSubTypes.h @@ -0,0 +1,153 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "CurvatureConfidence.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + +} // 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 ~CurvatureConfidencePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURECONFIDENCE_PUBSUBTYPES_H_ + 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..382a8e3ff5e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvaturePubSubTypes.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 CurvaturePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CurvaturePubSubTypes.h" +#include "CurvatureCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +CurvaturePubSubType::CurvaturePubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::Curvature_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Curvature::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_Curvature_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CurvaturePubSubType::~CurvaturePubSubType() +{ +} + +bool CurvaturePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CurvaturePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CurvaturePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..c3ca2121087 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvaturePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "Curvature.h" + +#include "CurvatureConfidencePubSubTypes.h" +#include "CurvatureValuePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~CurvaturePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATURE_PUBSUBTYPES_H_ + 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..c22add6736e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValue.cxx @@ -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 CurvatureValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace CurvatureValue_Constants { + + +} // namespace CurvatureValue_Constants + + +CurvatureValue::CurvatureValue() +{ +} + +CurvatureValue::~CurvatureValue() +{ +} + +CurvatureValue::CurvatureValue( + const CurvatureValue& x) +{ + m_value = x.m_value; +} + +CurvatureValue::CurvatureValue( + CurvatureValue&& x) noexcept +{ + m_value = x.m_value; +} + +CurvatureValue& CurvatureValue::operator =( + const CurvatureValue& x) +{ + + m_value = x.m_value; + return *this; +} + +CurvatureValue& CurvatureValue::operator =( + CurvatureValue&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool CurvatureValue::operator ==( + const CurvatureValue& x) const +{ + return (m_value == x.m_value); +} + +bool CurvatureValue::operator !=( + const CurvatureValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void CurvatureValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t CurvatureValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& CurvatureValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CurvatureValueCdrAux.ipp" + 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..b0b87805624 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValue.h @@ -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 CurvatureValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValueCdrAux.hpp new file mode 100644 index 00000000000..2c63891ad5a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValueCdrAux.hpp @@ -0,0 +1,59 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CurvatureValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUECDRAUX_HPP_ + +#include "CurvatureValue.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_CurvatureValue_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_CurvatureValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CurvatureValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValueCdrAux.ipp new file mode 100644 index 00000000000..f8fa4d52ea2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValueCdrAux.ipp @@ -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 CurvatureValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUECDRAUX_IPP_ + +#include "CurvatureValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::CurvatureValue& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CurvatureValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::CurvatureValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::CurvatureValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUECDRAUX_IPP_ + 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..b9380197b1d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValuePubSubTypes.cxx @@ -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 CurvatureValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CurvatureValuePubSubTypes.h" +#include "CurvatureValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CurvatureValue::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_CurvatureValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CurvatureValuePubSubType::~CurvatureValuePubSubType() +{ +} + +bool CurvatureValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CurvatureValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CurvatureValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..1dac9299fad --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/CurvatureValuePubSubTypes.h @@ -0,0 +1,145 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "CurvatureValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + +} // 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 ~CurvatureValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_CURVATUREVALUE_PUBSUBTYPES_H_ + 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..1e2072b24eb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasic.cxx @@ -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 DangerousGoodsBasic.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace DangerousGoodsBasic_Constants { + + +} // namespace DangerousGoodsBasic_Constants + + +DangerousGoodsBasic::DangerousGoodsBasic() +{ +} + +DangerousGoodsBasic::~DangerousGoodsBasic() +{ +} + +DangerousGoodsBasic::DangerousGoodsBasic( + const DangerousGoodsBasic& x) +{ + m_value = x.m_value; +} + +DangerousGoodsBasic::DangerousGoodsBasic( + DangerousGoodsBasic&& x) noexcept +{ + m_value = x.m_value; +} + +DangerousGoodsBasic& DangerousGoodsBasic::operator =( + const DangerousGoodsBasic& x) +{ + + m_value = x.m_value; + return *this; +} + +DangerousGoodsBasic& DangerousGoodsBasic::operator =( + DangerousGoodsBasic&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool DangerousGoodsBasic::operator ==( + const DangerousGoodsBasic& x) const +{ + return (m_value == x.m_value); +} + +bool DangerousGoodsBasic::operator !=( + const DangerousGoodsBasic& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void DangerousGoodsBasic::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t DangerousGoodsBasic::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& DangerousGoodsBasic::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "DangerousGoodsBasicCdrAux.ipp" + 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..2bab63e7e04 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasic.h @@ -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 DangerousGoodsBasic.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace DangerousGoodsBasic_Constants { + +const uint8_t EXPLOSIVES1 = 0; +const uint8_t EXPLOSIVES2 = 1; +const uint8_t EXPLOSIVES3 = 2; +const uint8_t EXPLOSIVES4 = 3; +const uint8_t EXPLOSIVES5 = 4; +const uint8_t EXPLOSIVES6 = 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASIC_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicCdrAux.hpp new file mode 100644 index 00000000000..0a34a207332 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicCdrAux.hpp @@ -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 DangerousGoodsBasicCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASICCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASICCDRAUX_HPP_ + +#include "DangerousGoodsBasic.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_DangerousGoodsBasic_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_DangerousGoodsBasic_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DangerousGoodsBasic& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASICCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicCdrAux.ipp new file mode 100644 index 00000000000..0faa4811101 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicCdrAux.ipp @@ -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 DangerousGoodsBasicCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASICCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASICCDRAUX_IPP_ + +#include "DangerousGoodsBasicCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::DangerousGoodsBasic& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DangerousGoodsBasic& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::DangerousGoodsBasic& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DangerousGoodsBasic& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASICCDRAUX_IPP_ + 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..9a3234fa092 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicPubSubTypes.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 DangerousGoodsBasicPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "DangerousGoodsBasicPubSubTypes.h" +#include "DangerousGoodsBasicCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DangerousGoodsBasic::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_DangerousGoodsBasic_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +DangerousGoodsBasicPubSubType::~DangerousGoodsBasicPubSubType() +{ +} + +bool DangerousGoodsBasicPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool DangerousGoodsBasicPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function DangerousGoodsBasicPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..c27e5f6c7aa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsBasicPubSubTypes.h @@ -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 DangerousGoodsBasicPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "DangerousGoodsBasic.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~DangerousGoodsBasicPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSBASIC_PUBSUBTYPES_H_ + 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..a67d901602a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainer.cxx @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +DangerousGoodsContainer::DangerousGoodsContainer() +{ +} + +DangerousGoodsContainer::~DangerousGoodsContainer() +{ +} + +DangerousGoodsContainer::DangerousGoodsContainer( + const DangerousGoodsContainer& x) +{ + m_dangerous_goods_basic = x.m_dangerous_goods_basic; +} + +DangerousGoodsContainer::DangerousGoodsContainer( + DangerousGoodsContainer&& x) noexcept +{ + m_dangerous_goods_basic = std::move(x.m_dangerous_goods_basic); +} + +DangerousGoodsContainer& DangerousGoodsContainer::operator =( + const DangerousGoodsContainer& x) +{ + + m_dangerous_goods_basic = x.m_dangerous_goods_basic; + return *this; +} + +DangerousGoodsContainer& DangerousGoodsContainer::operator =( + DangerousGoodsContainer&& x) noexcept +{ + + m_dangerous_goods_basic = std::move(x.m_dangerous_goods_basic); + return *this; +} + +bool DangerousGoodsContainer::operator ==( + const DangerousGoodsContainer& x) const +{ + return (m_dangerous_goods_basic == x.m_dangerous_goods_basic); +} + +bool DangerousGoodsContainer::operator !=( + const DangerousGoodsContainer& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& DangerousGoodsContainer::dangerous_goods_basic() +{ + return m_dangerous_goods_basic; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "DangerousGoodsContainerCdrAux.ipp" + 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..7fef171a26d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainer.h @@ -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 DangerousGoodsContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "DangerousGoodsBasic.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerCdrAux.hpp new file mode 100644 index 00000000000..24bb4ff43d5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DangerousGoodsContainerCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINERCDRAUX_HPP_ + +#include "DangerousGoodsContainer.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_DangerousGoodsContainer_max_cdr_typesize {9UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_DangerousGoodsContainer_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DangerousGoodsContainer& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerCdrAux.ipp new file mode 100644 index 00000000000..94682912338 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerCdrAux.ipp @@ -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 DangerousGoodsContainerCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINERCDRAUX_IPP_ + +#include "DangerousGoodsContainerCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::DangerousGoodsContainer& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.dangerous_goods_basic(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DangerousGoodsContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.dangerous_goods_basic() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::DangerousGoodsContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.dangerous_goods_basic(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DangerousGoodsContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINERCDRAUX_IPP_ + 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..5b93d58eae8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerPubSubTypes.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 DangerousGoodsContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "DangerousGoodsContainerPubSubTypes.h" +#include "DangerousGoodsContainerCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +DangerousGoodsContainerPubSubType::DangerousGoodsContainerPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::DangerousGoodsContainer_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DangerousGoodsContainer::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_DangerousGoodsContainer_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +DangerousGoodsContainerPubSubType::~DangerousGoodsContainerPubSubType() +{ +} + +bool DangerousGoodsContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool DangerousGoodsContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function DangerousGoodsContainerPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..c0f3d8ed96d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DangerousGoodsContainerPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "DangerousGoodsContainer.h" + +#include "DangerousGoodsBasicPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~DangerousGoodsContainerPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DANGEROUSGOODSCONTAINER_PUBSUBTYPES_H_ + 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..8f9389b72a9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitude.cxx @@ -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 DeltaAltitude.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace DeltaAltitude_Constants { + + +} // namespace DeltaAltitude_Constants + + +DeltaAltitude::DeltaAltitude() +{ +} + +DeltaAltitude::~DeltaAltitude() +{ +} + +DeltaAltitude::DeltaAltitude( + const DeltaAltitude& x) +{ + m_value = x.m_value; +} + +DeltaAltitude::DeltaAltitude( + DeltaAltitude&& x) noexcept +{ + m_value = x.m_value; +} + +DeltaAltitude& DeltaAltitude::operator =( + const DeltaAltitude& x) +{ + + m_value = x.m_value; + return *this; +} + +DeltaAltitude& DeltaAltitude::operator =( + DeltaAltitude&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool DeltaAltitude::operator ==( + const DeltaAltitude& x) const +{ + return (m_value == x.m_value); +} + +bool DeltaAltitude::operator !=( + const DeltaAltitude& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void DeltaAltitude::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t DeltaAltitude::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& DeltaAltitude::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "DeltaAltitudeCdrAux.ipp" + 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..84b8e14a11b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitude.h @@ -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 DeltaAltitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudeCdrAux.hpp new file mode 100644 index 00000000000..2b2f197b7c4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudeCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DeltaAltitudeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDECDRAUX_HPP_ + +#include "DeltaAltitude.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_DeltaAltitude_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_DeltaAltitude_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaAltitude& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudeCdrAux.ipp new file mode 100644 index 00000000000..1c2d202f9f0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudeCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DeltaAltitudeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDECDRAUX_IPP_ + +#include "DeltaAltitudeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::DeltaAltitude& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaAltitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::DeltaAltitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaAltitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDECDRAUX_IPP_ + 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..560ee7fa9f3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "DeltaAltitudePubSubTypes.h" +#include "DeltaAltitudeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DeltaAltitude::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_DeltaAltitude_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +DeltaAltitudePubSubType::~DeltaAltitudePubSubType() +{ +} + +bool DeltaAltitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool DeltaAltitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function DeltaAltitudePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..e4797122e10 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaAltitudePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "DeltaAltitude.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~DeltaAltitudePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAALTITUDE_PUBSUBTYPES_H_ + 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..dae6aee8086 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitude.cxx @@ -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 DeltaLatitude.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace DeltaLatitude_Constants { + + +} // namespace DeltaLatitude_Constants + + +DeltaLatitude::DeltaLatitude() +{ +} + +DeltaLatitude::~DeltaLatitude() +{ +} + +DeltaLatitude::DeltaLatitude( + const DeltaLatitude& x) +{ + m_value = x.m_value; +} + +DeltaLatitude::DeltaLatitude( + DeltaLatitude&& x) noexcept +{ + m_value = x.m_value; +} + +DeltaLatitude& DeltaLatitude::operator =( + const DeltaLatitude& x) +{ + + m_value = x.m_value; + return *this; +} + +DeltaLatitude& DeltaLatitude::operator =( + DeltaLatitude&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool DeltaLatitude::operator ==( + const DeltaLatitude& x) const +{ + return (m_value == x.m_value); +} + +bool DeltaLatitude::operator !=( + const DeltaLatitude& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void DeltaLatitude::value( + int32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int32_t DeltaLatitude::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int32_t& DeltaLatitude::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "DeltaLatitudeCdrAux.ipp" + 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..eb36579c768 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitude.h @@ -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 DeltaLatitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int32_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudeCdrAux.hpp new file mode 100644 index 00000000000..630d2451811 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudeCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DeltaLatitudeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDECDRAUX_HPP_ + +#include "DeltaLatitude.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_DeltaLatitude_max_cdr_typesize {8UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_DeltaLatitude_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaLatitude& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudeCdrAux.ipp new file mode 100644 index 00000000000..d73b6189966 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudeCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DeltaLatitudeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDECDRAUX_IPP_ + +#include "DeltaLatitudeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::DeltaLatitude& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaLatitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::DeltaLatitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaLatitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDECDRAUX_IPP_ + 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..0603d93f815 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "DeltaLatitudePubSubTypes.h" +#include "DeltaLatitudeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DeltaLatitude::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_DeltaLatitude_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +DeltaLatitudePubSubType::~DeltaLatitudePubSubType() +{ +} + +bool DeltaLatitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool DeltaLatitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function DeltaLatitudePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..a9ceb44747d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLatitudePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "DeltaLatitude.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~DeltaLatitudePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALATITUDE_PUBSUBTYPES_H_ + 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..4364211d349 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitude.cxx @@ -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 DeltaLongitude.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace DeltaLongitude_Constants { + + +} // namespace DeltaLongitude_Constants + + +DeltaLongitude::DeltaLongitude() +{ +} + +DeltaLongitude::~DeltaLongitude() +{ +} + +DeltaLongitude::DeltaLongitude( + const DeltaLongitude& x) +{ + m_value = x.m_value; +} + +DeltaLongitude::DeltaLongitude( + DeltaLongitude&& x) noexcept +{ + m_value = x.m_value; +} + +DeltaLongitude& DeltaLongitude::operator =( + const DeltaLongitude& x) +{ + + m_value = x.m_value; + return *this; +} + +DeltaLongitude& DeltaLongitude::operator =( + DeltaLongitude&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool DeltaLongitude::operator ==( + const DeltaLongitude& x) const +{ + return (m_value == x.m_value); +} + +bool DeltaLongitude::operator !=( + const DeltaLongitude& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void DeltaLongitude::value( + int32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int32_t DeltaLongitude::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int32_t& DeltaLongitude::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "DeltaLongitudeCdrAux.ipp" + 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..b20a185286b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitude.h @@ -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 DeltaLongitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int32_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudeCdrAux.hpp new file mode 100644 index 00000000000..7f02c930af5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudeCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DeltaLongitudeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDECDRAUX_HPP_ + +#include "DeltaLongitude.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_DeltaLongitude_max_cdr_typesize {8UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_DeltaLongitude_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaLongitude& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudeCdrAux.ipp new file mode 100644 index 00000000000..69fc42a8758 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudeCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DeltaLongitudeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDECDRAUX_IPP_ + +#include "DeltaLongitudeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::DeltaLongitude& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaLongitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::DeltaLongitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaLongitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDECDRAUX_IPP_ + 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..4c8afc70392 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "DeltaLongitudePubSubTypes.h" +#include "DeltaLongitudeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DeltaLongitude::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_DeltaLongitude_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +DeltaLongitudePubSubType::~DeltaLongitudePubSubType() +{ +} + +bool DeltaLongitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool DeltaLongitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function DeltaLongitudePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..b86543f6b2e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaLongitudePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "DeltaLongitude.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~DeltaLongitudePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTALONGITUDE_PUBSUBTYPES_H_ + 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..1e7359782c6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePosition.cxx @@ -0,0 +1,229 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +DeltaReferencePosition::DeltaReferencePosition() +{ +} + +DeltaReferencePosition::~DeltaReferencePosition() +{ +} + +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; +} + +DeltaReferencePosition::DeltaReferencePosition( + DeltaReferencePosition&& x) noexcept +{ + 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); +} + +DeltaReferencePosition& 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; +} + +DeltaReferencePosition& DeltaReferencePosition::operator =( + DeltaReferencePosition&& x) noexcept +{ + + 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 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 DeltaReferencePosition::operator !=( + const DeltaReferencePosition& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member delta_latitude + * @param _delta_latitude New value to be copied in member delta_latitude + */ +void 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 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& 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& 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 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 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& 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& 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 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 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& 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& DeltaReferencePosition::delta_altitude() +{ + return m_delta_altitude; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "DeltaReferencePositionCdrAux.ipp" + 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..6e1ddd13440 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePosition.h @@ -0,0 +1,235 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITION_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "DeltaLongitude.h" +#include "DeltaAltitude.h" +#include "DeltaLatitude.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionCdrAux.hpp new file mode 100644 index 00000000000..3b662b7edbc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DeltaReferencePositionCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITIONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITIONCDRAUX_HPP_ + +#include "DeltaReferencePosition.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_DeltaReferencePosition_max_cdr_typesize {26UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_DeltaReferencePosition_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaReferencePosition& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITIONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionCdrAux.ipp new file mode 100644 index 00000000000..7b4741c623d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DeltaReferencePositionCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITIONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITIONCDRAUX_IPP_ + +#include "DeltaReferencePositionCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::DeltaReferencePosition& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.delta_latitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.delta_longitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.delta_altitude(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaReferencePosition& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.delta_latitude() + << eprosima::fastcdr::MemberId(1) << data.delta_longitude() + << eprosima::fastcdr::MemberId(2) << data.delta_altitude() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::DeltaReferencePosition& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.delta_latitude(); + break; + + case 1: + dcdr >> data.delta_longitude(); + break; + + case 2: + dcdr >> data.delta_altitude(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DeltaReferencePosition& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITIONCDRAUX_IPP_ + 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..07d019f5e98 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionPubSubTypes.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 DeltaReferencePositionPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "DeltaReferencePositionPubSubTypes.h" +#include "DeltaReferencePositionCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +DeltaReferencePositionPubSubType::DeltaReferencePositionPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::DeltaReferencePosition_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DeltaReferencePosition::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_DeltaReferencePosition_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +DeltaReferencePositionPubSubType::~DeltaReferencePositionPubSubType() +{ +} + +bool DeltaReferencePositionPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool DeltaReferencePositionPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function DeltaReferencePositionPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..add5601c8fb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DeltaReferencePositionPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "DeltaReferencePosition.h" + +#include "DeltaLongitudePubSubTypes.h" +#include "DeltaAltitudePubSubTypes.h" +#include "DeltaLatitudePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~DeltaReferencePositionPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DELTAREFERENCEPOSITION_PUBSUBTYPES_H_ + 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..6e192d9680c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirection.cxx @@ -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 DriveDirection.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace DriveDirection_Constants { + + +} // namespace DriveDirection_Constants + + +DriveDirection::DriveDirection() +{ +} + +DriveDirection::~DriveDirection() +{ +} + +DriveDirection::DriveDirection( + const DriveDirection& x) +{ + m_value = x.m_value; +} + +DriveDirection::DriveDirection( + DriveDirection&& x) noexcept +{ + m_value = x.m_value; +} + +DriveDirection& DriveDirection::operator =( + const DriveDirection& x) +{ + + m_value = x.m_value; + return *this; +} + +DriveDirection& DriveDirection::operator =( + DriveDirection&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool DriveDirection::operator ==( + const DriveDirection& x) const +{ + return (m_value == x.m_value); +} + +bool DriveDirection::operator !=( + const DriveDirection& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void DriveDirection::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t DriveDirection::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& DriveDirection::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "DriveDirectionCdrAux.ipp" + 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..38d1e451e1e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirection.h @@ -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 DriveDirection.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTION_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionCdrAux.hpp new file mode 100644 index 00000000000..6b3b35ad57b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DriveDirectionCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTIONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTIONCDRAUX_HPP_ + +#include "DriveDirection.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_DriveDirection_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_DriveDirection_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DriveDirection& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTIONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionCdrAux.ipp new file mode 100644 index 00000000000..17c9668af63 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DriveDirectionCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTIONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTIONCDRAUX_IPP_ + +#include "DriveDirectionCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::DriveDirection& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DriveDirection& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::DriveDirection& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DriveDirection& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTIONCDRAUX_IPP_ + 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..6e39d1b2107 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionPubSubTypes.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 DriveDirectionPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "DriveDirectionPubSubTypes.h" +#include "DriveDirectionCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DriveDirection::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_DriveDirection_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +DriveDirectionPubSubType::~DriveDirectionPubSubType() +{ +} + +bool DriveDirectionPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool DriveDirectionPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function DriveDirectionPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..efdfe03a7ce --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DriveDirectionPubSubTypes.h @@ -0,0 +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 DriveDirectionPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "DriveDirection.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + +} // 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 ~DriveDirectionPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVEDIRECTION_PUBSUBTYPES_H_ + 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..4dcfdcaa828 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatus.cxx @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace DrivingLaneStatus_Constants { + + +} // namespace DrivingLaneStatus_Constants + + +DrivingLaneStatus::DrivingLaneStatus() +{ +} + +DrivingLaneStatus::~DrivingLaneStatus() +{ +} + +DrivingLaneStatus::DrivingLaneStatus( + const DrivingLaneStatus& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +DrivingLaneStatus::DrivingLaneStatus( + DrivingLaneStatus&& x) noexcept +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +DrivingLaneStatus& DrivingLaneStatus::operator =( + const DrivingLaneStatus& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + return *this; +} + +DrivingLaneStatus& DrivingLaneStatus::operator =( + DrivingLaneStatus&& x) noexcept +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + return *this; +} + +bool DrivingLaneStatus::operator ==( + const DrivingLaneStatus& x) const +{ + return (m_value == x.m_value && + m_bits_unused == x.m_bits_unused); +} + +bool DrivingLaneStatus::operator !=( + const DrivingLaneStatus& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void 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 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& DrivingLaneStatus::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& 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 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 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& DrivingLaneStatus::bits_unused() +{ + return m_bits_unused; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "DrivingLaneStatusCdrAux.ipp" + 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..05cfd7fe633 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatus.h @@ -0,0 +1,203 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_value; + uint8_t m_bits_unused{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusCdrAux.hpp new file mode 100644 index 00000000000..805c078370c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusCdrAux.hpp @@ -0,0 +1,55 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file DrivingLaneStatusCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUSCDRAUX_HPP_ + +#include "DrivingLaneStatus.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_DrivingLaneStatus_max_cdr_typesize {109UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_DrivingLaneStatus_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DrivingLaneStatus& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusCdrAux.ipp new file mode 100644 index 00000000000..dc8fbd342e8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusCdrAux.ipp @@ -0,0 +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 DrivingLaneStatusCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUSCDRAUX_IPP_ + +#include "DrivingLaneStatusCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::DrivingLaneStatus& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.bits_unused(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DrivingLaneStatus& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() + << eprosima::fastcdr::MemberId(1) << data.bits_unused() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::DrivingLaneStatus& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + case 1: + dcdr >> data.bits_unused(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::DrivingLaneStatus& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUSCDRAUX_IPP_ + 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..3180536716a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusPubSubTypes.cxx @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "DrivingLaneStatusPubSubTypes.h" +#include "DrivingLaneStatusCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(DrivingLaneStatus::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_DrivingLaneStatus_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +DrivingLaneStatusPubSubType::~DrivingLaneStatusPubSubType() +{ +} + +bool DrivingLaneStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool DrivingLaneStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function DrivingLaneStatusPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace etsi_its_cam_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusPubSubTypes.h new file mode 100644 index 00000000000..e0eb62287e5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/DrivingLaneStatusPubSubTypes.h @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "DrivingLaneStatus.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated DrivingLaneStatus 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 DrivingLaneStatus_Constants { + + + + +} // namespace DrivingLaneStatus_Constants + + + +/*! + * @brief This class represents the TopicDataType of the type DrivingLaneStatus defined by the user in the IDL file. + * @ingroup DrivingLaneStatus + */ +class DrivingLaneStatusPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef DrivingLaneStatus type; + + eProsima_user_DllExport DrivingLaneStatusPubSubType(); + + eProsima_user_DllExport ~DrivingLaneStatusPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_DRIVINGLANESTATUS_PUBSUBTYPES_H_ + 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..ff3e382d189 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatus.cxx @@ -0,0 +1,131 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +EmbarkationStatus::EmbarkationStatus() +{ +} + +EmbarkationStatus::~EmbarkationStatus() +{ +} + +EmbarkationStatus::EmbarkationStatus( + const EmbarkationStatus& x) +{ + m_value = x.m_value; +} + +EmbarkationStatus::EmbarkationStatus( + EmbarkationStatus&& x) noexcept +{ + m_value = x.m_value; +} + +EmbarkationStatus& EmbarkationStatus::operator =( + const EmbarkationStatus& x) +{ + + m_value = x.m_value; + return *this; +} + +EmbarkationStatus& EmbarkationStatus::operator =( + EmbarkationStatus&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool EmbarkationStatus::operator ==( + const EmbarkationStatus& x) const +{ + return (m_value == x.m_value); +} + +bool EmbarkationStatus::operator !=( + const EmbarkationStatus& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void EmbarkationStatus::value( + bool _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +bool EmbarkationStatus::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +bool& EmbarkationStatus::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "EmbarkationStatusCdrAux.ipp" + 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..53c99ed7745 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatus.h @@ -0,0 +1,169 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + bool m_value{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusCdrAux.hpp new file mode 100644 index 00000000000..dd5e19edc45 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file EmbarkationStatusCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUSCDRAUX_HPP_ + +#include "EmbarkationStatus.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_EmbarkationStatus_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_EmbarkationStatus_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::EmbarkationStatus& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusCdrAux.ipp new file mode 100644 index 00000000000..47bcf075558 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusCdrAux.ipp @@ -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 EmbarkationStatusCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUSCDRAUX_IPP_ + +#include "EmbarkationStatusCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::EmbarkationStatus& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::EmbarkationStatus& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::EmbarkationStatus& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::EmbarkationStatus& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUSCDRAUX_IPP_ + 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..4285c4af794 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusPubSubTypes.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 EmbarkationStatusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "EmbarkationStatusPubSubTypes.h" +#include "EmbarkationStatusCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +EmbarkationStatusPubSubType::EmbarkationStatusPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::EmbarkationStatus_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(EmbarkationStatus::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_EmbarkationStatus_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +EmbarkationStatusPubSubType::~EmbarkationStatusPubSubType() +{ +} + +bool EmbarkationStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool EmbarkationStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function EmbarkationStatusPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..c54b22b2543 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmbarkationStatusPubSubTypes.h @@ -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 EmbarkationStatusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "EmbarkationStatus.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~EmbarkationStatusPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMBARKATIONSTATUS_PUBSUBTYPES_H_ + 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..7907f755323 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainer.cxx @@ -0,0 +1,297 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +EmergencyContainer::EmergencyContainer() +{ +} + +EmergencyContainer::~EmergencyContainer() +{ +} + +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; +} + +EmergencyContainer::EmergencyContainer( + EmergencyContainer&& x) noexcept +{ + 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; +} + +EmergencyContainer& 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; +} + +EmergencyContainer& EmergencyContainer::operator =( + EmergencyContainer&& x) noexcept +{ + + 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 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 EmergencyContainer::operator !=( + const EmergencyContainer& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& EmergencyContainer::emergency_priority_is_present() +{ + return m_emergency_priority_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "EmergencyContainerCdrAux.ipp" + 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..453d0b5319c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainer.h @@ -0,0 +1,277 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "CauseCode.h" +#include "EmergencyPriority.h" +#include "LightBarSirenInUse.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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{false}; + etsi_its_cam_msgs::msg::EmergencyPriority m_emergency_priority; + bool m_emergency_priority_is_present{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINER_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerCdrAux.hpp new file mode 100644 index 00000000000..ef4c109e1a5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file EmergencyContainerCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINERCDRAUX_HPP_ + +#include "EmergencyContainer.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_EmergencyContainer_max_cdr_typesize {246UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_EmergencyContainer_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::EmergencyContainer& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerCdrAux.ipp new file mode 100644 index 00000000000..e45181e6495 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerCdrAux.ipp @@ -0,0 +1,162 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file EmergencyContainerCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINERCDRAUX_IPP_ + +#include "EmergencyContainerCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::EmergencyContainer& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.light_bar_siren_in_use(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.incident_indication(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.incident_indication_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.emergency_priority(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.emergency_priority_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::EmergencyContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.light_bar_siren_in_use() + << eprosima::fastcdr::MemberId(1) << data.incident_indication() + << eprosima::fastcdr::MemberId(2) << data.incident_indication_is_present() + << eprosima::fastcdr::MemberId(3) << data.emergency_priority() + << eprosima::fastcdr::MemberId(4) << data.emergency_priority_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::EmergencyContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.light_bar_siren_in_use(); + break; + + case 1: + dcdr >> data.incident_indication(); + break; + + case 2: + dcdr >> data.incident_indication_is_present(); + break; + + case 3: + dcdr >> data.emergency_priority(); + break; + + case 4: + dcdr >> data.emergency_priority_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::EmergencyContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINERCDRAUX_IPP_ + 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..36d8b7548e1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerPubSubTypes.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 EmergencyContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "EmergencyContainerPubSubTypes.h" +#include "EmergencyContainerCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +EmergencyContainerPubSubType::EmergencyContainerPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::EmergencyContainer_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(EmergencyContainer::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_EmergencyContainer_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +EmergencyContainerPubSubType::~EmergencyContainerPubSubType() +{ +} + +bool EmergencyContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool EmergencyContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function EmergencyContainerPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..703d916ea38 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyContainerPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "EmergencyContainer.h" + +#include "CauseCodePubSubTypes.h" +#include "EmergencyPriorityPubSubTypes.h" +#include "LightBarSirenInUsePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~EmergencyContainerPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYCONTAINER_PUBSUBTYPES_H_ + 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..82bfe1f1b44 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriority.cxx @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace EmergencyPriority_Constants { + + +} // namespace EmergencyPriority_Constants + + +EmergencyPriority::EmergencyPriority() +{ +} + +EmergencyPriority::~EmergencyPriority() +{ +} + +EmergencyPriority::EmergencyPriority( + const EmergencyPriority& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +EmergencyPriority::EmergencyPriority( + EmergencyPriority&& x) noexcept +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +EmergencyPriority& EmergencyPriority::operator =( + const EmergencyPriority& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + return *this; +} + +EmergencyPriority& EmergencyPriority::operator =( + EmergencyPriority&& x) noexcept +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + return *this; +} + +bool EmergencyPriority::operator ==( + const EmergencyPriority& x) const +{ + return (m_value == x.m_value && + m_bits_unused == x.m_bits_unused); +} + +bool EmergencyPriority::operator !=( + const EmergencyPriority& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void 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 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& EmergencyPriority::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& 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 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 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& EmergencyPriority::bits_unused() +{ + return m_bits_unused; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "EmergencyPriorityCdrAux.ipp" + 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..b357132b76d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriority.h @@ -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 EmergencyPriority.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_value; + uint8_t m_bits_unused{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITY_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityCdrAux.hpp new file mode 100644 index 00000000000..1d0e75c16aa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file EmergencyPriorityCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITYCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITYCDRAUX_HPP_ + +#include "EmergencyPriority.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_EmergencyPriority_max_cdr_typesize {109UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_EmergencyPriority_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::EmergencyPriority& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITYCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityCdrAux.ipp new file mode 100644 index 00000000000..f7597ede851 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityCdrAux.ipp @@ -0,0 +1,145 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file EmergencyPriorityCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITYCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITYCDRAUX_IPP_ + +#include "EmergencyPriorityCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::EmergencyPriority& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.bits_unused(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::EmergencyPriority& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() + << eprosima::fastcdr::MemberId(1) << data.bits_unused() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::EmergencyPriority& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + case 1: + dcdr >> data.bits_unused(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::EmergencyPriority& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITYCDRAUX_IPP_ + 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..1c1bdee6c29 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityPubSubTypes.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 EmergencyPriorityPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "EmergencyPriorityPubSubTypes.h" +#include "EmergencyPriorityCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(EmergencyPriority::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_EmergencyPriority_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +EmergencyPriorityPubSubType::~EmergencyPriorityPubSubType() +{ +} + +bool EmergencyPriorityPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool EmergencyPriorityPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function EmergencyPriorityPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..0e966c40324 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/EmergencyPriorityPubSubTypes.h @@ -0,0 +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 EmergencyPriorityPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "EmergencyPriority.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + +} // 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 ~EmergencyPriorityPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EMERGENCYPRIORITY_PUBSUBTYPES_H_ + 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..82ba9fe758e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLights.cxx @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace ExteriorLights_Constants { + + +} // namespace ExteriorLights_Constants + + +ExteriorLights::ExteriorLights() +{ +} + +ExteriorLights::~ExteriorLights() +{ +} + +ExteriorLights::ExteriorLights( + const ExteriorLights& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +ExteriorLights::ExteriorLights( + ExteriorLights&& x) noexcept +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +ExteriorLights& ExteriorLights::operator =( + const ExteriorLights& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + return *this; +} + +ExteriorLights& ExteriorLights::operator =( + ExteriorLights&& x) noexcept +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + return *this; +} + +bool ExteriorLights::operator ==( + const ExteriorLights& x) const +{ + return (m_value == x.m_value && + m_bits_unused == x.m_bits_unused); +} + +bool ExteriorLights::operator !=( + const ExteriorLights& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void 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 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& ExteriorLights::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& 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 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 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& ExteriorLights::bits_unused() +{ + return m_bits_unused; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ExteriorLightsCdrAux.ipp" + 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..2f631572b74 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLights.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 ExteriorLights.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_value; + uint8_t m_bits_unused{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsCdrAux.hpp new file mode 100644 index 00000000000..9d7b629f34a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsCdrAux.hpp @@ -0,0 +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 ExteriorLightsCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTSCDRAUX_HPP_ + +#include "ExteriorLights.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_ExteriorLights_max_cdr_typesize {109UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_ExteriorLights_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ExteriorLights& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsCdrAux.ipp new file mode 100644 index 00000000000..2db74b6dace --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsCdrAux.ipp @@ -0,0 +1,157 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ExteriorLightsCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTSCDRAUX_IPP_ + +#include "ExteriorLightsCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::ExteriorLights& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.bits_unused(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ExteriorLights& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() + << eprosima::fastcdr::MemberId(1) << data.bits_unused() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::ExteriorLights& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + case 1: + dcdr >> data.bits_unused(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ExteriorLights& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTSCDRAUX_IPP_ + 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..093ae1e8de1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsPubSubTypes.cxx @@ -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 ExteriorLightsPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ExteriorLightsPubSubTypes.h" +#include "ExteriorLightsCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ExteriorLights::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_ExteriorLights_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ExteriorLightsPubSubType::~ExteriorLightsPubSubType() +{ +} + +bool ExteriorLightsPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ExteriorLightsPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ExteriorLightsPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..1e154d4d3f7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ExteriorLightsPubSubTypes.h @@ -0,0 +1,155 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ExteriorLights.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + +} // 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 ~ExteriorLightsPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_EXTERIORLIGHTS_PUBSUBTYPES_H_ + 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..6977ad30d92 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTime.cxx @@ -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 GenerationDeltaTime.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace GenerationDeltaTime_Constants { + + +} // namespace GenerationDeltaTime_Constants + + +GenerationDeltaTime::GenerationDeltaTime() +{ +} + +GenerationDeltaTime::~GenerationDeltaTime() +{ +} + +GenerationDeltaTime::GenerationDeltaTime( + const GenerationDeltaTime& x) +{ + m_value = x.m_value; +} + +GenerationDeltaTime::GenerationDeltaTime( + GenerationDeltaTime&& x) noexcept +{ + m_value = x.m_value; +} + +GenerationDeltaTime& GenerationDeltaTime::operator =( + const GenerationDeltaTime& x) +{ + + m_value = x.m_value; + return *this; +} + +GenerationDeltaTime& GenerationDeltaTime::operator =( + GenerationDeltaTime&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool GenerationDeltaTime::operator ==( + const GenerationDeltaTime& x) const +{ + return (m_value == x.m_value); +} + +bool GenerationDeltaTime::operator !=( + const GenerationDeltaTime& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void GenerationDeltaTime::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t GenerationDeltaTime::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& GenerationDeltaTime::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "GenerationDeltaTimeCdrAux.ipp" + 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..26b4d1d69d2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTime.h @@ -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 GenerationDeltaTime.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIME_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimeCdrAux.hpp new file mode 100644 index 00000000000..2e2fa37bd83 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimeCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file GenerationDeltaTimeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIMECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIMECDRAUX_HPP_ + +#include "GenerationDeltaTime.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_GenerationDeltaTime_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_GenerationDeltaTime_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::GenerationDeltaTime& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIMECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimeCdrAux.ipp new file mode 100644 index 00000000000..b229122dbb0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimeCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file GenerationDeltaTimeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIMECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIMECDRAUX_IPP_ + +#include "GenerationDeltaTimeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::GenerationDeltaTime& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::GenerationDeltaTime& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::GenerationDeltaTime& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::GenerationDeltaTime& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIMECDRAUX_IPP_ + 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..a294465098a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimePubSubTypes.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 GenerationDeltaTimePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "GenerationDeltaTimePubSubTypes.h" +#include "GenerationDeltaTimeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(GenerationDeltaTime::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_GenerationDeltaTime_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +GenerationDeltaTimePubSubType::~GenerationDeltaTimePubSubType() +{ +} + +bool GenerationDeltaTimePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool GenerationDeltaTimePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function GenerationDeltaTimePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..4844dc0f3df --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/GenerationDeltaTimePubSubTypes.h @@ -0,0 +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 GenerationDeltaTimePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "GenerationDeltaTime.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + +} // 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 ~GenerationDeltaTimePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_GENERATIONDELTATIME_PUBSUBTYPES_H_ + 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..5dc56e50f0f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatus.cxx @@ -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 HardShoulderStatus.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace HardShoulderStatus_Constants { + + +} // namespace HardShoulderStatus_Constants + + +HardShoulderStatus::HardShoulderStatus() +{ +} + +HardShoulderStatus::~HardShoulderStatus() +{ +} + +HardShoulderStatus::HardShoulderStatus( + const HardShoulderStatus& x) +{ + m_value = x.m_value; +} + +HardShoulderStatus::HardShoulderStatus( + HardShoulderStatus&& x) noexcept +{ + m_value = x.m_value; +} + +HardShoulderStatus& HardShoulderStatus::operator =( + const HardShoulderStatus& x) +{ + + m_value = x.m_value; + return *this; +} + +HardShoulderStatus& HardShoulderStatus::operator =( + HardShoulderStatus&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool HardShoulderStatus::operator ==( + const HardShoulderStatus& x) const +{ + return (m_value == x.m_value); +} + +bool HardShoulderStatus::operator !=( + const HardShoulderStatus& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void HardShoulderStatus::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t HardShoulderStatus::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& HardShoulderStatus::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "HardShoulderStatusCdrAux.ipp" + 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..42619c8fc9c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatus.h @@ -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 HardShoulderStatus.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusCdrAux.hpp new file mode 100644 index 00000000000..3ef7f64a7e6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HardShoulderStatusCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUSCDRAUX_HPP_ + +#include "HardShoulderStatus.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_HardShoulderStatus_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_HardShoulderStatus_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HardShoulderStatus& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusCdrAux.ipp new file mode 100644 index 00000000000..009ead23d8a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HardShoulderStatusCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUSCDRAUX_IPP_ + +#include "HardShoulderStatusCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::HardShoulderStatus& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HardShoulderStatus& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::HardShoulderStatus& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HardShoulderStatus& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUSCDRAUX_IPP_ + 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..e30653c4183 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusPubSubTypes.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 HardShoulderStatusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "HardShoulderStatusPubSubTypes.h" +#include "HardShoulderStatusCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(HardShoulderStatus::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_HardShoulderStatus_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +HardShoulderStatusPubSubType::~HardShoulderStatusPubSubType() +{ +} + +bool HardShoulderStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool HardShoulderStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function HardShoulderStatusPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..b6a92e010b9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HardShoulderStatusPubSubTypes.h @@ -0,0 +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 HardShoulderStatusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "HardShoulderStatus.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + +} // 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 ~HardShoulderStatusPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HARDSHOULDERSTATUS_PUBSUBTYPES_H_ + 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..83296bf9255 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Heading.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 Heading.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +Heading::Heading() +{ +} + +Heading::~Heading() +{ +} + +Heading::Heading( + const Heading& x) +{ + m_heading_value = x.m_heading_value; + m_heading_confidence = x.m_heading_confidence; +} + +Heading::Heading( + Heading&& x) noexcept +{ + m_heading_value = std::move(x.m_heading_value); + m_heading_confidence = std::move(x.m_heading_confidence); +} + +Heading& Heading::operator =( + const Heading& x) +{ + + m_heading_value = x.m_heading_value; + m_heading_confidence = x.m_heading_confidence; + return *this; +} + +Heading& Heading::operator =( + Heading&& x) noexcept +{ + + m_heading_value = std::move(x.m_heading_value); + m_heading_confidence = std::move(x.m_heading_confidence); + return *this; +} + +bool Heading::operator ==( + const Heading& x) const +{ + return (m_heading_value == x.m_heading_value && + m_heading_confidence == x.m_heading_confidence); +} + +bool Heading::operator !=( + const Heading& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member heading_value + * @param _heading_value New value to be copied in member heading_value + */ +void 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 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& 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& 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 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 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& 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& Heading::heading_confidence() +{ + return m_heading_confidence; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "HeadingCdrAux.ipp" + 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..1aa86a0329d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Heading.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADING_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADING_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "HeadingConfidence.h" +#include "HeadingValue.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingCdrAux.hpp new file mode 100644 index 00000000000..9c964569323 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HeadingCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCDRAUX_HPP_ + +#include "Heading.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_Heading_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_Heading_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Heading& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingCdrAux.ipp new file mode 100644 index 00000000000..4f575a69372 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HeadingCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCDRAUX_IPP_ + +#include "HeadingCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::Heading& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.heading_value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.heading_confidence(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Heading& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.heading_value() + << eprosima::fastcdr::MemberId(1) << data.heading_confidence() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::Heading& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.heading_value(); + break; + + case 1: + dcdr >> data.heading_confidence(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Heading& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCDRAUX_IPP_ + 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..35bfad72b4b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidence.cxx @@ -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 HeadingConfidence.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace HeadingConfidence_Constants { + + +} // namespace HeadingConfidence_Constants + + +HeadingConfidence::HeadingConfidence() +{ +} + +HeadingConfidence::~HeadingConfidence() +{ +} + +HeadingConfidence::HeadingConfidence( + const HeadingConfidence& x) +{ + m_value = x.m_value; +} + +HeadingConfidence::HeadingConfidence( + HeadingConfidence&& x) noexcept +{ + m_value = x.m_value; +} + +HeadingConfidence& HeadingConfidence::operator =( + const HeadingConfidence& x) +{ + + m_value = x.m_value; + return *this; +} + +HeadingConfidence& HeadingConfidence::operator =( + HeadingConfidence&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool HeadingConfidence::operator ==( + const HeadingConfidence& x) const +{ + return (m_value == x.m_value); +} + +bool HeadingConfidence::operator !=( + const HeadingConfidence& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void HeadingConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t HeadingConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& HeadingConfidence::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "HeadingConfidenceCdrAux.ipp" + 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..dbe824c5972 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidence.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidenceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidenceCdrAux.hpp new file mode 100644 index 00000000000..3c96dfecbb9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidenceCdrAux.hpp @@ -0,0 +1,63 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HeadingConfidenceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCECDRAUX_HPP_ + +#include "HeadingConfidence.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_HeadingConfidence_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_HeadingConfidence_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HeadingConfidence& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidenceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidenceCdrAux.ipp new file mode 100644 index 00000000000..f9b6024d3b1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidenceCdrAux.ipp @@ -0,0 +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 HeadingConfidenceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCECDRAUX_IPP_ + +#include "HeadingConfidenceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::HeadingConfidence& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HeadingConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::HeadingConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HeadingConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCECDRAUX_IPP_ + 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..7e621329e29 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidencePubSubTypes.cxx @@ -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 HeadingConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "HeadingConfidencePubSubTypes.h" +#include "HeadingConfidenceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(HeadingConfidence::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_HeadingConfidence_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +HeadingConfidencePubSubType::~HeadingConfidencePubSubType() +{ +} + +bool HeadingConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool HeadingConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function HeadingConfidencePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..5ff4381d450 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingConfidencePubSubTypes.h @@ -0,0 +1,149 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "HeadingConfidence.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + +} // 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 ~HeadingConfidencePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGCONFIDENCE_PUBSUBTYPES_H_ + 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..d7e7330a482 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingPubSubTypes.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 HeadingPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "HeadingPubSubTypes.h" +#include "HeadingCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +HeadingPubSubType::HeadingPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::Heading_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Heading::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_Heading_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +HeadingPubSubType::~HeadingPubSubType() +{ +} + +bool HeadingPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool HeadingPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function HeadingPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..456546810e7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "Heading.h" + +#include "HeadingConfidencePubSubTypes.h" +#include "HeadingValuePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~HeadingPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADING_PUBSUBTYPES_H_ + 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..c9cab6ca5a1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValue.cxx @@ -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 HeadingValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace HeadingValue_Constants { + + +} // namespace HeadingValue_Constants + + +HeadingValue::HeadingValue() +{ +} + +HeadingValue::~HeadingValue() +{ +} + +HeadingValue::HeadingValue( + const HeadingValue& x) +{ + m_value = x.m_value; +} + +HeadingValue::HeadingValue( + HeadingValue&& x) noexcept +{ + m_value = x.m_value; +} + +HeadingValue& HeadingValue::operator =( + const HeadingValue& x) +{ + + m_value = x.m_value; + return *this; +} + +HeadingValue& HeadingValue::operator =( + HeadingValue&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool HeadingValue::operator ==( + const HeadingValue& x) const +{ + return (m_value == x.m_value); +} + +bool HeadingValue::operator !=( + const HeadingValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void HeadingValue::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t HeadingValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& HeadingValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "HeadingValueCdrAux.ipp" + 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..07908da9035 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValue.h @@ -0,0 +1,180 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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 WGS84_NORTH = 0; +const uint16_t WGS84_EAST = 900; +const uint16_t WGS84_SOUTH = 1800; +const uint16_t WGS84_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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValueCdrAux.hpp new file mode 100644 index 00000000000..444265b2e3d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValueCdrAux.hpp @@ -0,0 +1,65 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HeadingValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUECDRAUX_HPP_ + +#include "HeadingValue.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_HeadingValue_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_HeadingValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HeadingValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValueCdrAux.ipp new file mode 100644 index 00000000000..a3ff8b4113a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValueCdrAux.ipp @@ -0,0 +1,145 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HeadingValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUECDRAUX_IPP_ + +#include "HeadingValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::HeadingValue& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HeadingValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::HeadingValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HeadingValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUECDRAUX_IPP_ + 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..06a9540fa1f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValuePubSubTypes.cxx @@ -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 HeadingValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "HeadingValuePubSubTypes.h" +#include "HeadingValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(HeadingValue::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_HeadingValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +HeadingValuePubSubType::~HeadingValuePubSubType() +{ +} + +bool HeadingValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool HeadingValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function HeadingValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..219b9b972f0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HeadingValuePubSubTypes.h @@ -0,0 +1,151 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "HeadingValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + +} // 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 ~HeadingValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HEADINGVALUE_PUBSUBTYPES_H_ + 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..a72247d0c1d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainer.cxx @@ -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 HighFrequencyContainer.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace HighFrequencyContainer_Constants { + + +} // namespace HighFrequencyContainer_Constants + + +HighFrequencyContainer::HighFrequencyContainer() +{ +} + +HighFrequencyContainer::~HighFrequencyContainer() +{ +} + +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; +} + +HighFrequencyContainer::HighFrequencyContainer( + HighFrequencyContainer&& x) noexcept +{ + 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); +} + +HighFrequencyContainer& 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; +} + +HighFrequencyContainer& HighFrequencyContainer::operator =( + HighFrequencyContainer&& x) noexcept +{ + + 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 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 HighFrequencyContainer::operator !=( + const HighFrequencyContainer& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member choice + * @param _choice New value for member choice + */ +void HighFrequencyContainer::choice( + uint8_t _choice) +{ + m_choice = _choice; +} + +/*! + * @brief This function returns the value of member choice + * @return Value of member choice + */ +uint8_t HighFrequencyContainer::choice() const +{ + return m_choice; +} + +/*! + * @brief This function returns a reference to member choice + * @return Reference to member choice + */ +uint8_t& 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 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 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& 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& 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 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 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& 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& HighFrequencyContainer::rsu_container_high_frequency() +{ + return m_rsu_container_high_frequency; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "HighFrequencyContainerCdrAux.ipp" + 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..d5ffff825a5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainer.h @@ -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 HighFrequencyContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "RSUContainerHighFrequency.h" +#include "BasicVehicleContainerHighFrequency.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_choice{0}; + 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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerCdrAux.hpp new file mode 100644 index 00000000000..51ea3db1235 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerCdrAux.hpp @@ -0,0 +1,64 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HighFrequencyContainerCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINERCDRAUX_HPP_ + +#include "HighFrequencyContainer.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_HighFrequencyContainer_max_cdr_typesize {6798UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_HighFrequencyContainer_max_key_cdr_typesize {0UL}; + + + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HighFrequencyContainer& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerCdrAux.ipp new file mode 100644 index 00000000000..dce98ca104c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerCdrAux.ipp @@ -0,0 +1,151 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HighFrequencyContainerCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINERCDRAUX_IPP_ + +#include "HighFrequencyContainerCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::HighFrequencyContainer& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.choice(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.basic_vehicle_container_high_frequency(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.rsu_container_high_frequency(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HighFrequencyContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.choice() + << eprosima::fastcdr::MemberId(1) << data.basic_vehicle_container_high_frequency() + << eprosima::fastcdr::MemberId(2) << data.rsu_container_high_frequency() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::HighFrequencyContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.choice(); + break; + + case 1: + dcdr >> data.basic_vehicle_container_high_frequency(); + break; + + case 2: + dcdr >> data.rsu_container_high_frequency(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::HighFrequencyContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINERCDRAUX_IPP_ + 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..c0f2bc58e5a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerPubSubTypes.cxx @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "HighFrequencyContainerPubSubTypes.h" +#include "HighFrequencyContainerCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(HighFrequencyContainer::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_HighFrequencyContainer_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +HighFrequencyContainerPubSubType::~HighFrequencyContainerPubSubType() +{ +} + +bool HighFrequencyContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool HighFrequencyContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function HighFrequencyContainerPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..807e84a1ba6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/HighFrequencyContainerPubSubTypes.h @@ -0,0 +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 HighFrequencyContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "HighFrequencyContainer.h" + +#include "RSUContainerHighFrequencyPubSubTypes.h" +#include "BasicVehicleContainerHighFrequencyPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + +} // 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 ~HighFrequencyContainerPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_HIGHFREQUENCYCONTAINER_PUBSUBTYPES_H_ + 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..2f2a5012686 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeader.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 ItsPduHeader.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace ItsPduHeader_Constants { + + +} // namespace ItsPduHeader_Constants + + +ItsPduHeader::ItsPduHeader() +{ +} + +ItsPduHeader::~ItsPduHeader() +{ +} + +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; +} + +ItsPduHeader::ItsPduHeader( + ItsPduHeader&& x) noexcept +{ + m_protocol_version = x.m_protocol_version; + m_message_id = x.m_message_id; + m_station_id = std::move(x.m_station_id); +} + +ItsPduHeader& 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; +} + +ItsPduHeader& ItsPduHeader::operator =( + ItsPduHeader&& x) noexcept +{ + + 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 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 ItsPduHeader::operator !=( + const ItsPduHeader& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member protocol_version + * @param _protocol_version New value for member protocol_version + */ +void 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 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& 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 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 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& 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 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 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& 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& ItsPduHeader::station_id() +{ + return m_station_id; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ItsPduHeaderCdrAux.ipp" + 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..ddd6bbc3a5a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeader.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 ItsPduHeader.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "StationID.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_protocol_version{0}; + uint8_t m_message_id{0}; + 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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderCdrAux.hpp new file mode 100644 index 00000000000..4028be0b464 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderCdrAux.hpp @@ -0,0 +1,85 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ItsPduHeaderCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADERCDRAUX_HPP_ + +#include "ItsPduHeader.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_ItsPduHeader_max_cdr_typesize {16UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_ItsPduHeader_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ItsPduHeader& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderCdrAux.ipp new file mode 100644 index 00000000000..1830046bdd6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderCdrAux.ipp @@ -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 ItsPduHeaderCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADERCDRAUX_IPP_ + +#include "ItsPduHeaderCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::ItsPduHeader& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.protocol_version(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.message_id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.station_id(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ItsPduHeader& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.protocol_version() + << eprosima::fastcdr::MemberId(1) << data.message_id() + << eprosima::fastcdr::MemberId(2) << data.station_id() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::ItsPduHeader& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.protocol_version(); + break; + + case 1: + dcdr >> data.message_id(); + break; + + case 2: + dcdr >> data.station_id(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ItsPduHeader& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADERCDRAUX_IPP_ + 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..4f5955ce2ab --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderPubSubTypes.cxx @@ -0,0 +1,236 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ItsPduHeaderPubSubTypes.h" +#include "ItsPduHeaderCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ItsPduHeader::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_ItsPduHeader_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ItsPduHeaderPubSubType::~ItsPduHeaderPubSubType() +{ +} + +bool ItsPduHeaderPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ItsPduHeaderPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ItsPduHeaderPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..e7f5cacc41f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ItsPduHeaderPubSubTypes.h @@ -0,0 +1,172 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ItsPduHeader.h" + +#include "StationIDPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~ItsPduHeaderPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ITSPDUHEADER_PUBSUBTYPES_H_ + 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..be0c8b88a52 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePosition.cxx @@ -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 LanePosition.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace LanePosition_Constants { + + +} // namespace LanePosition_Constants + + +LanePosition::LanePosition() +{ +} + +LanePosition::~LanePosition() +{ +} + +LanePosition::LanePosition( + const LanePosition& x) +{ + m_value = x.m_value; +} + +LanePosition::LanePosition( + LanePosition&& x) noexcept +{ + m_value = x.m_value; +} + +LanePosition& LanePosition::operator =( + const LanePosition& x) +{ + + m_value = x.m_value; + return *this; +} + +LanePosition& LanePosition::operator =( + LanePosition&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool LanePosition::operator ==( + const LanePosition& x) const +{ + return (m_value == x.m_value); +} + +bool LanePosition::operator !=( + const LanePosition& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void LanePosition::value( + int8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int8_t LanePosition::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int8_t& LanePosition::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "LanePositionCdrAux.ipp" + 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..2aaa79054ba --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePosition.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITION_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionCdrAux.hpp new file mode 100644 index 00000000000..b58a319e69b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionCdrAux.hpp @@ -0,0 +1,63 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LanePositionCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITIONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITIONCDRAUX_HPP_ + +#include "LanePosition.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_LanePosition_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_LanePosition_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LanePosition& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITIONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionCdrAux.ipp new file mode 100644 index 00000000000..ba920b13f4f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionCdrAux.ipp @@ -0,0 +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 LanePositionCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITIONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITIONCDRAUX_IPP_ + +#include "LanePositionCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::LanePosition& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LanePosition& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::LanePosition& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LanePosition& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITIONCDRAUX_IPP_ + 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..8c7f1710f70 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionPubSubTypes.cxx @@ -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 LanePositionPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "LanePositionPubSubTypes.h" +#include "LanePositionCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(LanePosition::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_LanePosition_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LanePositionPubSubType::~LanePositionPubSubType() +{ +} + +bool LanePositionPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LanePositionPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LanePositionPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..f3f48190f88 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LanePositionPubSubTypes.h @@ -0,0 +1,149 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "LanePosition.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + +} // 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 ~LanePositionPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LANEPOSITION_PUBSUBTYPES_H_ + 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..2611790c80a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAcceleration.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 LateralAcceleration.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +LateralAcceleration::LateralAcceleration() +{ +} + +LateralAcceleration::~LateralAcceleration() +{ +} + +LateralAcceleration::LateralAcceleration( + const LateralAcceleration& x) +{ + m_lateral_acceleration_value = x.m_lateral_acceleration_value; + m_lateral_acceleration_confidence = x.m_lateral_acceleration_confidence; +} + +LateralAcceleration::LateralAcceleration( + LateralAcceleration&& x) noexcept +{ + m_lateral_acceleration_value = std::move(x.m_lateral_acceleration_value); + m_lateral_acceleration_confidence = std::move(x.m_lateral_acceleration_confidence); +} + +LateralAcceleration& 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; +} + +LateralAcceleration& LateralAcceleration::operator =( + LateralAcceleration&& x) noexcept +{ + + 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 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 LateralAcceleration::operator !=( + const LateralAcceleration& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& LateralAcceleration::lateral_acceleration_confidence() +{ + return m_lateral_acceleration_confidence; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "LateralAccelerationCdrAux.ipp" + 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..7346e378d4b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAcceleration.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATION_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "AccelerationConfidence.h" +#include "LateralAccelerationValue.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationCdrAux.hpp new file mode 100644 index 00000000000..50bf827db92 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LateralAccelerationCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONCDRAUX_HPP_ + +#include "LateralAcceleration.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_LateralAcceleration_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_LateralAcceleration_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LateralAcceleration& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationCdrAux.ipp new file mode 100644 index 00000000000..4edc114fda6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LateralAccelerationCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONCDRAUX_IPP_ + +#include "LateralAccelerationCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::LateralAcceleration& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.lateral_acceleration_value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.lateral_acceleration_confidence(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LateralAcceleration& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.lateral_acceleration_value() + << eprosima::fastcdr::MemberId(1) << data.lateral_acceleration_confidence() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::LateralAcceleration& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.lateral_acceleration_value(); + break; + + case 1: + dcdr >> data.lateral_acceleration_confidence(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LateralAcceleration& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONCDRAUX_IPP_ + 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..c491f0cf725 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationPubSubTypes.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 LateralAccelerationPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "LateralAccelerationPubSubTypes.h" +#include "LateralAccelerationCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +LateralAccelerationPubSubType::LateralAccelerationPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::LateralAcceleration_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(LateralAcceleration::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_LateralAcceleration_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LateralAccelerationPubSubType::~LateralAccelerationPubSubType() +{ +} + +bool LateralAccelerationPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LateralAccelerationPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LateralAccelerationPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..b8e57bc4228 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "LateralAcceleration.h" + +#include "AccelerationConfidencePubSubTypes.h" +#include "LateralAccelerationValuePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~LateralAccelerationPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATION_PUBSUBTYPES_H_ + 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..a9bdff9ccb7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValue.cxx @@ -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 LateralAccelerationValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace LateralAccelerationValue_Constants { + + +} // namespace LateralAccelerationValue_Constants + + +LateralAccelerationValue::LateralAccelerationValue() +{ +} + +LateralAccelerationValue::~LateralAccelerationValue() +{ +} + +LateralAccelerationValue::LateralAccelerationValue( + const LateralAccelerationValue& x) +{ + m_value = x.m_value; +} + +LateralAccelerationValue::LateralAccelerationValue( + LateralAccelerationValue&& x) noexcept +{ + m_value = x.m_value; +} + +LateralAccelerationValue& LateralAccelerationValue::operator =( + const LateralAccelerationValue& x) +{ + + m_value = x.m_value; + return *this; +} + +LateralAccelerationValue& LateralAccelerationValue::operator =( + LateralAccelerationValue&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool LateralAccelerationValue::operator ==( + const LateralAccelerationValue& x) const +{ + return (m_value == x.m_value); +} + +bool LateralAccelerationValue::operator !=( + const LateralAccelerationValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void LateralAccelerationValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t LateralAccelerationValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& LateralAccelerationValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "LateralAccelerationValueCdrAux.ipp" + 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..36e352bfc0c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValue.h @@ -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 LateralAccelerationValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValueCdrAux.hpp new file mode 100644 index 00000000000..9a1878a3c09 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValueCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LateralAccelerationValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUECDRAUX_HPP_ + +#include "LateralAccelerationValue.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_LateralAccelerationValue_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_LateralAccelerationValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LateralAccelerationValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValueCdrAux.ipp new file mode 100644 index 00000000000..5dadf606d99 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValueCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LateralAccelerationValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUECDRAUX_IPP_ + +#include "LateralAccelerationValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::LateralAccelerationValue& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LateralAccelerationValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::LateralAccelerationValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LateralAccelerationValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUECDRAUX_IPP_ + 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..47d425684d2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValuePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "LateralAccelerationValuePubSubTypes.h" +#include "LateralAccelerationValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(LateralAccelerationValue::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_LateralAccelerationValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LateralAccelerationValuePubSubType::~LateralAccelerationValuePubSubType() +{ +} + +bool LateralAccelerationValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LateralAccelerationValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LateralAccelerationValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..ea199a2dbf6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LateralAccelerationValuePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "LateralAccelerationValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~LateralAccelerationValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATERALACCELERATIONVALUE_PUBSUBTYPES_H_ + 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..830820947be --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Latitude.cxx @@ -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 Latitude.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace Latitude_Constants { + + +} // namespace Latitude_Constants + + +Latitude::Latitude() +{ +} + +Latitude::~Latitude() +{ +} + +Latitude::Latitude( + const Latitude& x) +{ + m_value = x.m_value; +} + +Latitude::Latitude( + Latitude&& x) noexcept +{ + m_value = x.m_value; +} + +Latitude& Latitude::operator =( + const Latitude& x) +{ + + m_value = x.m_value; + return *this; +} + +Latitude& Latitude::operator =( + Latitude&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool Latitude::operator ==( + const Latitude& x) const +{ + return (m_value == x.m_value); +} + +bool Latitude::operator !=( + const Latitude& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void Latitude::value( + int32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int32_t Latitude::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int32_t& Latitude::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "LatitudeCdrAux.ipp" + 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..4af31471fbc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Latitude.h @@ -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 Latitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int32_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudeCdrAux.hpp new file mode 100644 index 00000000000..17e763e9033 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudeCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LatitudeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDECDRAUX_HPP_ + +#include "Latitude.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_Latitude_max_cdr_typesize {8UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_Latitude_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Latitude& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudeCdrAux.ipp new file mode 100644 index 00000000000..a8414d73a40 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudeCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LatitudeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDECDRAUX_IPP_ + +#include "LatitudeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::Latitude& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Latitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::Latitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Latitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDECDRAUX_IPP_ + 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..1e0350caeed --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "LatitudePubSubTypes.h" +#include "LatitudeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Latitude::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_Latitude_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LatitudePubSubType::~LatitudePubSubType() +{ +} + +bool LatitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LatitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LatitudePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..28c2b3260d1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LatitudePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "Latitude.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~LatitudePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LATITUDE_PUBSUBTYPES_H_ + 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..1e48faf37e5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUse.cxx @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace LightBarSirenInUse_Constants { + + +} // namespace LightBarSirenInUse_Constants + + +LightBarSirenInUse::LightBarSirenInUse() +{ +} + +LightBarSirenInUse::~LightBarSirenInUse() +{ +} + +LightBarSirenInUse::LightBarSirenInUse( + const LightBarSirenInUse& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +LightBarSirenInUse::LightBarSirenInUse( + LightBarSirenInUse&& x) noexcept +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +LightBarSirenInUse& LightBarSirenInUse::operator =( + const LightBarSirenInUse& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + return *this; +} + +LightBarSirenInUse& LightBarSirenInUse::operator =( + LightBarSirenInUse&& x) noexcept +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + return *this; +} + +bool LightBarSirenInUse::operator ==( + const LightBarSirenInUse& x) const +{ + return (m_value == x.m_value && + m_bits_unused == x.m_bits_unused); +} + +bool LightBarSirenInUse::operator !=( + const LightBarSirenInUse& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void 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 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& LightBarSirenInUse::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& 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 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 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& LightBarSirenInUse::bits_unused() +{ + return m_bits_unused; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "LightBarSirenInUseCdrAux.ipp" + 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..6ae6fc1869a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUse.h @@ -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 LightBarSirenInUse.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_value; + uint8_t m_bits_unused{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUseCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUseCdrAux.hpp new file mode 100644 index 00000000000..024ff6fd5b5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUseCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LightBarSirenInUseCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSECDRAUX_HPP_ + +#include "LightBarSirenInUse.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_LightBarSirenInUse_max_cdr_typesize {109UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_LightBarSirenInUse_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LightBarSirenInUse& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUseCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUseCdrAux.ipp new file mode 100644 index 00000000000..494fd57c8cf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUseCdrAux.ipp @@ -0,0 +1,145 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LightBarSirenInUseCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSECDRAUX_IPP_ + +#include "LightBarSirenInUseCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::LightBarSirenInUse& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.bits_unused(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LightBarSirenInUse& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() + << eprosima::fastcdr::MemberId(1) << data.bits_unused() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::LightBarSirenInUse& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + case 1: + dcdr >> data.bits_unused(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LightBarSirenInUse& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSECDRAUX_IPP_ + 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..b2abe1aa010 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUsePubSubTypes.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 LightBarSirenInUsePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "LightBarSirenInUsePubSubTypes.h" +#include "LightBarSirenInUseCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(LightBarSirenInUse::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_LightBarSirenInUse_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LightBarSirenInUsePubSubType::~LightBarSirenInUsePubSubType() +{ +} + +bool LightBarSirenInUsePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LightBarSirenInUsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LightBarSirenInUsePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..b5b75fedb7b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LightBarSirenInUsePubSubTypes.h @@ -0,0 +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 LightBarSirenInUsePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "LightBarSirenInUse.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + +} // 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 ~LightBarSirenInUsePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LIGHTBARSIRENINUSE_PUBSUBTYPES_H_ + 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..40d04b7dde3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Longitude.cxx @@ -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 Longitude.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace Longitude_Constants { + + +} // namespace Longitude_Constants + + +Longitude::Longitude() +{ +} + +Longitude::~Longitude() +{ +} + +Longitude::Longitude( + const Longitude& x) +{ + m_value = x.m_value; +} + +Longitude::Longitude( + Longitude&& x) noexcept +{ + m_value = x.m_value; +} + +Longitude& Longitude::operator =( + const Longitude& x) +{ + + m_value = x.m_value; + return *this; +} + +Longitude& Longitude::operator =( + Longitude&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool Longitude::operator ==( + const Longitude& x) const +{ + return (m_value == x.m_value); +} + +bool Longitude::operator !=( + const Longitude& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void Longitude::value( + int32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int32_t Longitude::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int32_t& Longitude::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "LongitudeCdrAux.ipp" + 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..2dbc6432de8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Longitude.h @@ -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 Longitude.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int32_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudeCdrAux.hpp new file mode 100644 index 00000000000..60f7c9d565a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudeCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LongitudeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDECDRAUX_HPP_ + +#include "Longitude.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_Longitude_max_cdr_typesize {8UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_Longitude_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Longitude& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudeCdrAux.ipp new file mode 100644 index 00000000000..d56017c8634 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudeCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LongitudeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDECDRAUX_IPP_ + +#include "LongitudeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::Longitude& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Longitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::Longitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Longitude& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDECDRAUX_IPP_ + 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..5b32639878d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "LongitudePubSubTypes.h" +#include "LongitudeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Longitude::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_Longitude_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LongitudePubSubType::~LongitudePubSubType() +{ +} + +bool LongitudePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LongitudePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LongitudePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..273e7e8d317 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "Longitude.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~LongitudePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDE_PUBSUBTYPES_H_ + 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..e12f7b0f32d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAcceleration.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 LongitudinalAcceleration.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +LongitudinalAcceleration::LongitudinalAcceleration() +{ +} + +LongitudinalAcceleration::~LongitudinalAcceleration() +{ +} + +LongitudinalAcceleration::LongitudinalAcceleration( + const LongitudinalAcceleration& x) +{ + m_longitudinal_acceleration_value = x.m_longitudinal_acceleration_value; + m_longitudinal_acceleration_confidence = x.m_longitudinal_acceleration_confidence; +} + +LongitudinalAcceleration::LongitudinalAcceleration( + LongitudinalAcceleration&& x) noexcept +{ + m_longitudinal_acceleration_value = std::move(x.m_longitudinal_acceleration_value); + m_longitudinal_acceleration_confidence = std::move(x.m_longitudinal_acceleration_confidence); +} + +LongitudinalAcceleration& 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; +} + +LongitudinalAcceleration& LongitudinalAcceleration::operator =( + LongitudinalAcceleration&& x) noexcept +{ + + 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 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 LongitudinalAcceleration::operator !=( + const LongitudinalAcceleration& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& LongitudinalAcceleration::longitudinal_acceleration_confidence() +{ + return m_longitudinal_acceleration_confidence; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "LongitudinalAccelerationCdrAux.ipp" + 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..d2cef677593 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAcceleration.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATION_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "LongitudinalAccelerationValue.h" +#include "AccelerationConfidence.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationCdrAux.hpp new file mode 100644 index 00000000000..eb41d127a28 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LongitudinalAccelerationCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONCDRAUX_HPP_ + +#include "LongitudinalAcceleration.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_LongitudinalAcceleration_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_LongitudinalAcceleration_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LongitudinalAcceleration& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationCdrAux.ipp new file mode 100644 index 00000000000..d790d4e2e68 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LongitudinalAccelerationCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONCDRAUX_IPP_ + +#include "LongitudinalAccelerationCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::LongitudinalAcceleration& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.longitudinal_acceleration_value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.longitudinal_acceleration_confidence(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LongitudinalAcceleration& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.longitudinal_acceleration_value() + << eprosima::fastcdr::MemberId(1) << data.longitudinal_acceleration_confidence() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::LongitudinalAcceleration& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.longitudinal_acceleration_value(); + break; + + case 1: + dcdr >> data.longitudinal_acceleration_confidence(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LongitudinalAcceleration& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONCDRAUX_IPP_ + 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..d3545613e6e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationPubSubTypes.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 LongitudinalAccelerationPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "LongitudinalAccelerationPubSubTypes.h" +#include "LongitudinalAccelerationCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +LongitudinalAccelerationPubSubType::LongitudinalAccelerationPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::LongitudinalAcceleration_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(LongitudinalAcceleration::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_LongitudinalAcceleration_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LongitudinalAccelerationPubSubType::~LongitudinalAccelerationPubSubType() +{ +} + +bool LongitudinalAccelerationPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LongitudinalAccelerationPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LongitudinalAccelerationPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..9f556f6cb37 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "LongitudinalAcceleration.h" + +#include "LongitudinalAccelerationValuePubSubTypes.h" +#include "AccelerationConfidencePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~LongitudinalAccelerationPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATION_PUBSUBTYPES_H_ + 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..31301393849 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.cxx @@ -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 LongitudinalAccelerationValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace LongitudinalAccelerationValue_Constants { + + +} // namespace LongitudinalAccelerationValue_Constants + + +LongitudinalAccelerationValue::LongitudinalAccelerationValue() +{ +} + +LongitudinalAccelerationValue::~LongitudinalAccelerationValue() +{ +} + +LongitudinalAccelerationValue::LongitudinalAccelerationValue( + const LongitudinalAccelerationValue& x) +{ + m_value = x.m_value; +} + +LongitudinalAccelerationValue::LongitudinalAccelerationValue( + LongitudinalAccelerationValue&& x) noexcept +{ + m_value = x.m_value; +} + +LongitudinalAccelerationValue& LongitudinalAccelerationValue::operator =( + const LongitudinalAccelerationValue& x) +{ + + m_value = x.m_value; + return *this; +} + +LongitudinalAccelerationValue& LongitudinalAccelerationValue::operator =( + LongitudinalAccelerationValue&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool LongitudinalAccelerationValue::operator ==( + const LongitudinalAccelerationValue& x) const +{ + return (m_value == x.m_value); +} + +bool LongitudinalAccelerationValue::operator !=( + const LongitudinalAccelerationValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void LongitudinalAccelerationValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t LongitudinalAccelerationValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& LongitudinalAccelerationValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "LongitudinalAccelerationValueCdrAux.ipp" + 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..be615524c9f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValue.h @@ -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 LongitudinalAccelerationValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValueCdrAux.hpp new file mode 100644 index 00000000000..54261bcf0e1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValueCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LongitudinalAccelerationValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUECDRAUX_HPP_ + +#include "LongitudinalAccelerationValue.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_LongitudinalAccelerationValue_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_LongitudinalAccelerationValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValueCdrAux.ipp new file mode 100644 index 00000000000..3fd3db4b8dd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValueCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LongitudinalAccelerationValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUECDRAUX_IPP_ + +#include "LongitudinalAccelerationValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LongitudinalAccelerationValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUECDRAUX_IPP_ + 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..6d8cb06a870 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValuePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "LongitudinalAccelerationValuePubSubTypes.h" +#include "LongitudinalAccelerationValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(LongitudinalAccelerationValue::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_LongitudinalAccelerationValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LongitudinalAccelerationValuePubSubType::~LongitudinalAccelerationValuePubSubType() +{ +} + +bool LongitudinalAccelerationValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LongitudinalAccelerationValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LongitudinalAccelerationValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..782b4f5e252 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LongitudinalAccelerationValuePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "LongitudinalAccelerationValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~LongitudinalAccelerationValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LONGITUDINALACCELERATIONVALUE_PUBSUBTYPES_H_ + 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..86268900144 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainer.cxx @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace LowFrequencyContainer_Constants { + + +} // namespace LowFrequencyContainer_Constants + + +LowFrequencyContainer::LowFrequencyContainer() +{ +} + +LowFrequencyContainer::~LowFrequencyContainer() +{ +} + +LowFrequencyContainer::LowFrequencyContainer( + const LowFrequencyContainer& x) +{ + m_choice = x.m_choice; + m_basic_vehicle_container_low_frequency = x.m_basic_vehicle_container_low_frequency; +} + +LowFrequencyContainer::LowFrequencyContainer( + LowFrequencyContainer&& x) noexcept +{ + m_choice = x.m_choice; + m_basic_vehicle_container_low_frequency = std::move(x.m_basic_vehicle_container_low_frequency); +} + +LowFrequencyContainer& 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; +} + +LowFrequencyContainer& LowFrequencyContainer::operator =( + LowFrequencyContainer&& x) noexcept +{ + + m_choice = x.m_choice; + m_basic_vehicle_container_low_frequency = std::move(x.m_basic_vehicle_container_low_frequency); + return *this; +} + +bool 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 LowFrequencyContainer::operator !=( + const LowFrequencyContainer& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member choice + * @param _choice New value for member choice + */ +void LowFrequencyContainer::choice( + uint8_t _choice) +{ + m_choice = _choice; +} + +/*! + * @brief This function returns the value of member choice + * @return Value of member choice + */ +uint8_t LowFrequencyContainer::choice() const +{ + return m_choice; +} + +/*! + * @brief This function returns a reference to member choice + * @return Reference to member choice + */ +uint8_t& 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 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 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& 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& LowFrequencyContainer::basic_vehicle_container_low_frequency() +{ + return m_basic_vehicle_container_low_frequency; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "LowFrequencyContainerCdrAux.ipp" + 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..e5f202a4a57 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainer.h @@ -0,0 +1,203 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "BasicVehicleContainerLowFrequency.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_choice{0}; + 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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerCdrAux.hpp new file mode 100644 index 00000000000..1431b5c2d44 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerCdrAux.hpp @@ -0,0 +1,53 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LowFrequencyContainerCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINERCDRAUX_HPP_ + +#include "LowFrequencyContainer.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_LowFrequencyContainer_max_cdr_typesize {4143UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_LowFrequencyContainer_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LowFrequencyContainer& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerCdrAux.ipp new file mode 100644 index 00000000000..e31052b2a1f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file LowFrequencyContainerCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINERCDRAUX_IPP_ + +#include "LowFrequencyContainerCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::LowFrequencyContainer& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.choice(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.basic_vehicle_container_low_frequency(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LowFrequencyContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.choice() + << eprosima::fastcdr::MemberId(1) << data.basic_vehicle_container_low_frequency() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::LowFrequencyContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.choice(); + break; + + case 1: + dcdr >> data.basic_vehicle_container_low_frequency(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::LowFrequencyContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINERCDRAUX_IPP_ + 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..4abec5bad70 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerPubSubTypes.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 LowFrequencyContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "LowFrequencyContainerPubSubTypes.h" +#include "LowFrequencyContainerCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(LowFrequencyContainer::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_LowFrequencyContainer_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +LowFrequencyContainerPubSubType::~LowFrequencyContainerPubSubType() +{ +} + +bool LowFrequencyContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool LowFrequencyContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function LowFrequencyContainerPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace etsi_its_cam_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerPubSubTypes.h new file mode 100644 index 00000000000..7c11f043160 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/LowFrequencyContainerPubSubTypes.h @@ -0,0 +1,140 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "LowFrequencyContainer.h" + +#include "BasicVehicleContainerLowFrequencyPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated LowFrequencyContainer 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 LowFrequencyContainer_Constants { + + +} // namespace LowFrequencyContainer_Constants + + + +/*! + * @brief This class represents the TopicDataType of the type LowFrequencyContainer defined by the user in the IDL file. + * @ingroup LowFrequencyContainer + */ +class LowFrequencyContainerPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef LowFrequencyContainer type; + + eProsima_user_DllExport LowFrequencyContainerPubSubType(); + + eProsima_user_DllExport ~LowFrequencyContainerPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_LOWFREQUENCYCONTAINER_PUBSUBTYPES_H_ + 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..95c7643511a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTime.cxx @@ -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 PathDeltaTime.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace PathDeltaTime_Constants { + + +} // namespace PathDeltaTime_Constants + + +PathDeltaTime::PathDeltaTime() +{ +} + +PathDeltaTime::~PathDeltaTime() +{ +} + +PathDeltaTime::PathDeltaTime( + const PathDeltaTime& x) +{ + m_value = x.m_value; +} + +PathDeltaTime::PathDeltaTime( + PathDeltaTime&& x) noexcept +{ + m_value = x.m_value; +} + +PathDeltaTime& PathDeltaTime::operator =( + const PathDeltaTime& x) +{ + + m_value = x.m_value; + return *this; +} + +PathDeltaTime& PathDeltaTime::operator =( + PathDeltaTime&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool PathDeltaTime::operator ==( + const PathDeltaTime& x) const +{ + return (m_value == x.m_value); +} + +bool PathDeltaTime::operator !=( + const PathDeltaTime& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void PathDeltaTime::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t PathDeltaTime::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& PathDeltaTime::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PathDeltaTimeCdrAux.ipp" + 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..a2fe594c1a5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTime.h @@ -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 PathDeltaTime.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIME_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimeCdrAux.hpp new file mode 100644 index 00000000000..7116cd48782 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimeCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PathDeltaTimeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIMECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIMECDRAUX_HPP_ + +#include "PathDeltaTime.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_PathDeltaTime_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_PathDeltaTime_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PathDeltaTime& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIMECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimeCdrAux.ipp new file mode 100644 index 00000000000..6f5431f3c22 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimeCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PathDeltaTimeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIMECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIMECDRAUX_IPP_ + +#include "PathDeltaTimeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::PathDeltaTime& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PathDeltaTime& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::PathDeltaTime& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PathDeltaTime& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIMECDRAUX_IPP_ + 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..5c03d0b0116 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimePubSubTypes.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 PathDeltaTimePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PathDeltaTimePubSubTypes.h" +#include "PathDeltaTimeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PathDeltaTime::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_PathDeltaTime_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PathDeltaTimePubSubType::~PathDeltaTimePubSubType() +{ +} + +bool PathDeltaTimePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PathDeltaTimePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PathDeltaTimePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..20cc38564a4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathDeltaTimePubSubTypes.h @@ -0,0 +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 PathDeltaTimePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "PathDeltaTime.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + +} // 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 ~PathDeltaTimePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHDELTATIME_PUBSUBTYPES_H_ + 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..995701c2df2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistory.cxx @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace PathHistory_Constants { + + +} // namespace PathHistory_Constants + + + + +PathHistory::PathHistory() +{ +} + +PathHistory::~PathHistory() +{ +} + +PathHistory::PathHistory( + const PathHistory& x) +{ + m_array = x.m_array; +} + +PathHistory::PathHistory( + PathHistory&& x) noexcept +{ + m_array = std::move(x.m_array); +} + +PathHistory& PathHistory::operator =( + const PathHistory& x) +{ + + m_array = x.m_array; + return *this; +} + +PathHistory& PathHistory::operator =( + PathHistory&& x) noexcept +{ + + m_array = std::move(x.m_array); + return *this; +} + +bool PathHistory::operator ==( + const PathHistory& x) const +{ + return (m_array == x.m_array); +} + +bool PathHistory::operator !=( + const PathHistory& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member array + * @param _array New value to be copied in member array + */ +void 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 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& PathHistory::array() const +{ + return m_array; +} + +/*! + * @brief This function returns a reference to member array + * @return Reference to member array + */ +std::vector& PathHistory::array() +{ + return m_array; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PathHistoryCdrAux.ipp" + 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..ce7b7434f52 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistory.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 PathHistory.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORY_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORY_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "PathPoint.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_array; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORY_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryCdrAux.hpp new file mode 100644 index 00000000000..a3ea86c8161 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryCdrAux.hpp @@ -0,0 +1,59 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PathHistoryCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORYCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORYCDRAUX_HPP_ + +#include "PathHistory.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_PathHistory_max_cdr_typesize {4011UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_PathHistory_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PathHistory& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORYCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryCdrAux.ipp new file mode 100644 index 00000000000..e43ba93deb6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PathHistoryCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORYCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORYCDRAUX_IPP_ + +#include "PathHistoryCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::PathHistory& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.array(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PathHistory& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.array() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::PathHistory& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.array(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PathHistory& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORYCDRAUX_IPP_ + 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..de25e8139ba --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryPubSubTypes.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 PathHistoryPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PathHistoryPubSubTypes.h" +#include "PathHistoryCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PathHistory::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_PathHistory_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PathHistoryPubSubType::~PathHistoryPubSubType() +{ +} + +bool PathHistoryPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PathHistoryPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PathHistoryPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace etsi_its_cam_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryPubSubTypes.h new file mode 100644 index 00000000000..58f527bce29 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathHistoryPubSubTypes.h @@ -0,0 +1,144 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "PathHistory.h" + +#include "PathPointPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated PathHistory 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 PathHistory_Constants { + + + + +} // namespace PathHistory_Constants + + + + + +/*! + * @brief This class represents the TopicDataType of the type PathHistory defined by the user in the IDL file. + * @ingroup PathHistory + */ +class PathHistoryPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef PathHistory type; + + eProsima_user_DllExport PathHistoryPubSubType(); + + eProsima_user_DllExport ~PathHistoryPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHHISTORY_PUBSUBTYPES_H_ + 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..eec07083bc7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPoint.cxx @@ -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 PathPoint.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +PathPoint::PathPoint() +{ +} + +PathPoint::~PathPoint() +{ +} + +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; +} + +PathPoint::PathPoint( + PathPoint&& x) noexcept +{ + 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; +} + +PathPoint& 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; +} + +PathPoint& PathPoint::operator =( + PathPoint&& x) noexcept +{ + + 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 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 PathPoint::operator !=( + const PathPoint& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member path_position + * @param _path_position New value to be copied in member path_position + */ +void 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 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& 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& 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 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 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& 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& 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 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 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& PathPoint::path_delta_time_is_present() +{ + return m_path_delta_time_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PathPointCdrAux.ipp" + 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..592aca5bf11 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPoint.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 PathPoint.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINT_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINT_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "DeltaReferencePosition.h" +#include "PathDeltaTime.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINT_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointCdrAux.hpp new file mode 100644 index 00000000000..d652bc23f6b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PathPointCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINTCDRAUX_HPP_ + +#include "PathPoint.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_PathPoint_max_cdr_typesize {39UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_PathPoint_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PathPoint& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointCdrAux.ipp new file mode 100644 index 00000000000..40611f7861d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PathPointCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINTCDRAUX_IPP_ + +#include "PathPointCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::PathPoint& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.path_position(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.path_delta_time(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.path_delta_time_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PathPoint& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.path_position() + << eprosima::fastcdr::MemberId(1) << data.path_delta_time() + << eprosima::fastcdr::MemberId(2) << data.path_delta_time_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::PathPoint& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.path_position(); + break; + + case 1: + dcdr >> data.path_delta_time(); + break; + + case 2: + dcdr >> data.path_delta_time_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PathPoint& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINTCDRAUX_IPP_ + 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..f33ec2cf85d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointPubSubTypes.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 PathPointPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PathPointPubSubTypes.h" +#include "PathPointCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +PathPointPubSubType::PathPointPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::PathPoint_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PathPoint::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_PathPoint_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PathPointPubSubType::~PathPointPubSubType() +{ +} + +bool PathPointPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PathPointPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PathPointPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..c6e6ae83b8e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PathPointPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "PathPoint.h" + +#include "DeltaReferencePositionPubSubTypes.h" +#include "PathDeltaTimePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~PathPointPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PATHPOINT_PUBSUBTYPES_H_ + 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..9c81cc629bf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClass.cxx @@ -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 PerformanceClass.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace PerformanceClass_Constants { + + +} // namespace PerformanceClass_Constants + + +PerformanceClass::PerformanceClass() +{ +} + +PerformanceClass::~PerformanceClass() +{ +} + +PerformanceClass::PerformanceClass( + const PerformanceClass& x) +{ + m_value = x.m_value; +} + +PerformanceClass::PerformanceClass( + PerformanceClass&& x) noexcept +{ + m_value = x.m_value; +} + +PerformanceClass& PerformanceClass::operator =( + const PerformanceClass& x) +{ + + m_value = x.m_value; + return *this; +} + +PerformanceClass& PerformanceClass::operator =( + PerformanceClass&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool PerformanceClass::operator ==( + const PerformanceClass& x) const +{ + return (m_value == x.m_value); +} + +bool PerformanceClass::operator !=( + const PerformanceClass& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void PerformanceClass::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t PerformanceClass::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& PerformanceClass::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PerformanceClassCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClass.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClass.h new file mode 100644 index 00000000000..f331e367b5f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClass.h @@ -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 PerformanceClass.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 +#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(PERFORMANCECLASS_SOURCE) +#define PERFORMANCECLASS_DllAPI __declspec( dllexport ) +#else +#define PERFORMANCECLASS_DllAPI __declspec( dllimport ) +#endif // PERFORMANCECLASS_SOURCE +#else +#define PERFORMANCECLASS_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define PERFORMANCECLASS_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +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 PerformanceClass defined by the user in the IDL file. + * @ingroup PerformanceClass + */ +class PerformanceClass +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PerformanceClass(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PerformanceClass(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PerformanceClass that will be copied. + */ + eProsima_user_DllExport PerformanceClass( + const PerformanceClass& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::PerformanceClass that will be copied. + */ + eProsima_user_DllExport PerformanceClass( + PerformanceClass&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PerformanceClass that will be copied. + */ + eProsima_user_DllExport PerformanceClass& operator =( + const PerformanceClass& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::PerformanceClass that will be copied. + */ + eProsima_user_DllExport PerformanceClass& operator =( + PerformanceClass&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PerformanceClass object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PerformanceClass& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::PerformanceClass object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PerformanceClass& 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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassCdrAux.hpp new file mode 100644 index 00000000000..0e279bdd3c1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PerformanceClassCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASSCDRAUX_HPP_ + +#include "PerformanceClass.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_PerformanceClass_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_PerformanceClass_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PerformanceClass& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassCdrAux.ipp new file mode 100644 index 00000000000..7f1c3dee42e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PerformanceClassCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASSCDRAUX_IPP_ + +#include "PerformanceClassCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::PerformanceClass& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PerformanceClass& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::PerformanceClass& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PerformanceClass& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASSCDRAUX_IPP_ + 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..d209f413ac6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassPubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PerformanceClassPubSubTypes.h" +#include "PerformanceClassCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PerformanceClass::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_PerformanceClass_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PerformanceClassPubSubType::~PerformanceClassPubSubType() +{ +} + +bool PerformanceClassPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PerformanceClassPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PerformanceClassPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..0a82acd4fc6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PerformanceClassPubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "PerformanceClass.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~PerformanceClassPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PERFORMANCECLASS_PUBSUBTYPES_H_ + 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..09e6169dfa7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipse.cxx @@ -0,0 +1,229 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +PosConfidenceEllipse::PosConfidenceEllipse() +{ +} + +PosConfidenceEllipse::~PosConfidenceEllipse() +{ +} + +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; +} + +PosConfidenceEllipse::PosConfidenceEllipse( + PosConfidenceEllipse&& x) noexcept +{ + 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); +} + +PosConfidenceEllipse& 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; +} + +PosConfidenceEllipse& PosConfidenceEllipse::operator =( + PosConfidenceEllipse&& x) noexcept +{ + + 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 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 PosConfidenceEllipse::operator !=( + const PosConfidenceEllipse& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& 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 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 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& 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& PosConfidenceEllipse::semi_major_orientation() +{ + return m_semi_major_orientation; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PosConfidenceEllipseCdrAux.ipp" + 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..78f89d06246 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipse.h @@ -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 PosConfidenceEllipse.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "HeadingValue.h" +#include "SemiAxisLength.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipseCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipseCdrAux.hpp new file mode 100644 index 00000000000..b7969c3facd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipseCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PosConfidenceEllipseCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSECDRAUX_HPP_ + +#include "PosConfidenceEllipse.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_PosConfidenceEllipse_max_cdr_typesize {26UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_PosConfidenceEllipse_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PosConfidenceEllipse& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipseCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipseCdrAux.ipp new file mode 100644 index 00000000000..a6b958092fe --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipseCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PosConfidenceEllipseCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSECDRAUX_IPP_ + +#include "PosConfidenceEllipseCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::PosConfidenceEllipse& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.semi_major_confidence(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.semi_minor_confidence(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.semi_major_orientation(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PosConfidenceEllipse& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.semi_major_confidence() + << eprosima::fastcdr::MemberId(1) << data.semi_minor_confidence() + << eprosima::fastcdr::MemberId(2) << data.semi_major_orientation() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::PosConfidenceEllipse& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.semi_major_confidence(); + break; + + case 1: + dcdr >> data.semi_minor_confidence(); + break; + + case 2: + dcdr >> data.semi_major_orientation(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PosConfidenceEllipse& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSECDRAUX_IPP_ + 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..d41fcde2786 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipsePubSubTypes.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 PosConfidenceEllipsePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PosConfidenceEllipsePubSubTypes.h" +#include "PosConfidenceEllipseCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +PosConfidenceEllipsePubSubType::PosConfidenceEllipsePubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::PosConfidenceEllipse_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PosConfidenceEllipse::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_PosConfidenceEllipse_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PosConfidenceEllipsePubSubType::~PosConfidenceEllipsePubSubType() +{ +} + +bool PosConfidenceEllipsePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PosConfidenceEllipsePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PosConfidenceEllipsePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..22a3446a774 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PosConfidenceEllipsePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "PosConfidenceEllipse.h" + +#include "HeadingValuePubSubTypes.h" +#include "SemiAxisLengthPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~PosConfidenceEllipsePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_POSCONFIDENCEELLIPSE_PUBSUBTYPES_H_ + 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..c2b6bcfbeb9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.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 ProtectedCommunicationZone.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +ProtectedCommunicationZone::ProtectedCommunicationZone() +{ +} + +ProtectedCommunicationZone::~ProtectedCommunicationZone() +{ +} + +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; +} + +ProtectedCommunicationZone::ProtectedCommunicationZone( + ProtectedCommunicationZone&& x) noexcept +{ + 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; +} + +ProtectedCommunicationZone& 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; +} + +ProtectedCommunicationZone& ProtectedCommunicationZone::operator =( + ProtectedCommunicationZone&& x) noexcept +{ + + 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 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 ProtectedCommunicationZone::operator !=( + const ProtectedCommunicationZone& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& ProtectedCommunicationZone::protected_zone_id_is_present() +{ + return m_protected_zone_id_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ProtectedCommunicationZoneCdrAux.ipp" + 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..8bacee45c22 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZone.h @@ -0,0 +1,385 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ProtectedZoneRadius.h" +#include "TimestampIts.h" +#include "ProtectedZoneID.h" +#include "ProtectedZoneType.h" +#include "Latitude.h" +#include "Longitude.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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{false}; + 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{false}; + etsi_its_cam_msgs::msg::ProtectedZoneID m_protected_zone_id; + bool m_protected_zone_id_is_present{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZoneCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZoneCdrAux.hpp new file mode 100644 index 00000000000..946e04d797c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZoneCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ProtectedCommunicationZoneCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONECDRAUX_HPP_ + +#include "ProtectedCommunicationZone.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_ProtectedCommunicationZone_max_cdr_typesize {61UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_ProtectedCommunicationZone_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedCommunicationZone& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZoneCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZoneCdrAux.ipp new file mode 100644 index 00000000000..d21956ffa58 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZoneCdrAux.ipp @@ -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 ProtectedCommunicationZoneCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONECDRAUX_IPP_ + +#include "ProtectedCommunicationZoneCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::ProtectedCommunicationZone& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.protected_zone_type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.expiry_time(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.expiry_time_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.protected_zone_latitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.protected_zone_longitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.protected_zone_radius(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.protected_zone_radius_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.protected_zone_id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.protected_zone_id_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedCommunicationZone& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.protected_zone_type() + << eprosima::fastcdr::MemberId(1) << data.expiry_time() + << eprosima::fastcdr::MemberId(2) << data.expiry_time_is_present() + << eprosima::fastcdr::MemberId(3) << data.protected_zone_latitude() + << eprosima::fastcdr::MemberId(4) << data.protected_zone_longitude() + << eprosima::fastcdr::MemberId(5) << data.protected_zone_radius() + << eprosima::fastcdr::MemberId(6) << data.protected_zone_radius_is_present() + << eprosima::fastcdr::MemberId(7) << data.protected_zone_id() + << eprosima::fastcdr::MemberId(8) << data.protected_zone_id_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::ProtectedCommunicationZone& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.protected_zone_type(); + break; + + case 1: + dcdr >> data.expiry_time(); + break; + + case 2: + dcdr >> data.expiry_time_is_present(); + break; + + case 3: + dcdr >> data.protected_zone_latitude(); + break; + + case 4: + dcdr >> data.protected_zone_longitude(); + break; + + case 5: + dcdr >> data.protected_zone_radius(); + break; + + case 6: + dcdr >> data.protected_zone_radius_is_present(); + break; + + case 7: + dcdr >> data.protected_zone_id(); + break; + + case 8: + dcdr >> data.protected_zone_id_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedCommunicationZone& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONECDRAUX_IPP_ + 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..7445a4bd4de --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonePubSubTypes.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 ProtectedCommunicationZonePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ProtectedCommunicationZonePubSubTypes.h" +#include "ProtectedCommunicationZoneCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +ProtectedCommunicationZonePubSubType::ProtectedCommunicationZonePubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::ProtectedCommunicationZone_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ProtectedCommunicationZone::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_ProtectedCommunicationZone_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ProtectedCommunicationZonePubSubType::~ProtectedCommunicationZonePubSubType() +{ +} + +bool ProtectedCommunicationZonePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ProtectedCommunicationZonePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ProtectedCommunicationZonePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..460eee57468 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonePubSubTypes.h @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ProtectedCommunicationZone.h" + +#include "ProtectedZoneRadiusPubSubTypes.h" +#include "TimestampItsPubSubTypes.h" +#include "ProtectedZoneIDPubSubTypes.h" +#include "ProtectedZoneTypePubSubTypes.h" +#include "LatitudePubSubTypes.h" +#include "LongitudePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~ProtectedCommunicationZonePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONE_PUBSUBTYPES_H_ + 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..abe1878ba89 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.cxx @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace ProtectedCommunicationZonesRSU_Constants { + + +} // namespace ProtectedCommunicationZonesRSU_Constants + + + + +ProtectedCommunicationZonesRSU::ProtectedCommunicationZonesRSU() +{ +} + +ProtectedCommunicationZonesRSU::~ProtectedCommunicationZonesRSU() +{ +} + +ProtectedCommunicationZonesRSU::ProtectedCommunicationZonesRSU( + const ProtectedCommunicationZonesRSU& x) +{ + m_array = x.m_array; +} + +ProtectedCommunicationZonesRSU::ProtectedCommunicationZonesRSU( + ProtectedCommunicationZonesRSU&& x) noexcept +{ + m_array = std::move(x.m_array); +} + +ProtectedCommunicationZonesRSU& ProtectedCommunicationZonesRSU::operator =( + const ProtectedCommunicationZonesRSU& x) +{ + + m_array = x.m_array; + return *this; +} + +ProtectedCommunicationZonesRSU& ProtectedCommunicationZonesRSU::operator =( + ProtectedCommunicationZonesRSU&& x) noexcept +{ + + m_array = std::move(x.m_array); + return *this; +} + +bool ProtectedCommunicationZonesRSU::operator ==( + const ProtectedCommunicationZonesRSU& x) const +{ + return (m_array == x.m_array); +} + +bool ProtectedCommunicationZonesRSU::operator !=( + const ProtectedCommunicationZonesRSU& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member array + * @param _array New value to be copied in member array + */ +void 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 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& ProtectedCommunicationZonesRSU::array() const +{ + return m_array; +} + +/*! + * @brief This function returns a reference to member array + * @return Reference to member array + */ +std::vector& ProtectedCommunicationZonesRSU::array() +{ + return m_array; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ProtectedCommunicationZonesRSUCdrAux.ipp" + 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..97aa40a091f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSU.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 ProtectedCommunicationZonesRSU.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSU_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSU_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ProtectedCommunicationZone.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_array; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSU_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUCdrAux.hpp new file mode 100644 index 00000000000..af8e37adeb4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUCdrAux.hpp @@ -0,0 +1,59 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ProtectedCommunicationZonesRSUCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSUCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSUCDRAUX_HPP_ + +#include "ProtectedCommunicationZonesRSU.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_ProtectedCommunicationZonesRSU_max_cdr_typesize {6413UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_ProtectedCommunicationZonesRSU_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSUCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUCdrAux.ipp new file mode 100644 index 00000000000..718071b423e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ProtectedCommunicationZonesRSUCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSUCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSUCDRAUX_IPP_ + +#include "ProtectedCommunicationZonesRSUCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.array(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.array() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.array(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSUCDRAUX_IPP_ + 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..9eec8ec1229 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUPubSubTypes.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 ProtectedCommunicationZonesRSUPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ProtectedCommunicationZonesRSUPubSubTypes.h" +#include "ProtectedCommunicationZonesRSUCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ProtectedCommunicationZonesRSU::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_ProtectedCommunicationZonesRSU_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ProtectedCommunicationZonesRSUPubSubType::~ProtectedCommunicationZonesRSUPubSubType() +{ +} + +bool ProtectedCommunicationZonesRSUPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ProtectedCommunicationZonesRSUPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ProtectedCommunicationZonesRSUPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..85804e019f8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedCommunicationZonesRSUPubSubTypes.h @@ -0,0 +1,144 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ProtectedCommunicationZonesRSU.h" + +#include "ProtectedCommunicationZonePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + +} // 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 ~ProtectedCommunicationZonesRSUPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDCOMMUNICATIONZONESRSU_PUBSUBTYPES_H_ + 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..8eef65357dd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneID.cxx @@ -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 ProtectedZoneID.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace ProtectedZoneID_Constants { + + +} // namespace ProtectedZoneID_Constants + + +ProtectedZoneID::ProtectedZoneID() +{ +} + +ProtectedZoneID::~ProtectedZoneID() +{ +} + +ProtectedZoneID::ProtectedZoneID( + const ProtectedZoneID& x) +{ + m_value = x.m_value; +} + +ProtectedZoneID::ProtectedZoneID( + ProtectedZoneID&& x) noexcept +{ + m_value = x.m_value; +} + +ProtectedZoneID& ProtectedZoneID::operator =( + const ProtectedZoneID& x) +{ + + m_value = x.m_value; + return *this; +} + +ProtectedZoneID& ProtectedZoneID::operator =( + ProtectedZoneID&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool ProtectedZoneID::operator ==( + const ProtectedZoneID& x) const +{ + return (m_value == x.m_value); +} + +bool ProtectedZoneID::operator !=( + const ProtectedZoneID& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void ProtectedZoneID::value( + uint32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint32_t ProtectedZoneID::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint32_t& ProtectedZoneID::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ProtectedZoneIDCdrAux.ipp" + 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..3f765414fda --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneID.h @@ -0,0 +1,175 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint32_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEID_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDCdrAux.hpp new file mode 100644 index 00000000000..fa93c6e65b1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDCdrAux.hpp @@ -0,0 +1,55 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ProtectedZoneIDCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEIDCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEIDCDRAUX_HPP_ + +#include "ProtectedZoneID.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_ProtectedZoneID_max_cdr_typesize {8UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_ProtectedZoneID_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedZoneID& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEIDCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDCdrAux.ipp new file mode 100644 index 00000000000..de8bb1a2884 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDCdrAux.ipp @@ -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 ProtectedZoneIDCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEIDCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEIDCDRAUX_IPP_ + +#include "ProtectedZoneIDCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::ProtectedZoneID& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedZoneID& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::ProtectedZoneID& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedZoneID& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEIDCDRAUX_IPP_ + 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..1ce01804b15 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDPubSubTypes.cxx @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ProtectedZoneIDPubSubTypes.h" +#include "ProtectedZoneIDCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ProtectedZoneID::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_ProtectedZoneID_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ProtectedZoneIDPubSubType::~ProtectedZoneIDPubSubType() +{ +} + +bool ProtectedZoneIDPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ProtectedZoneIDPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ProtectedZoneIDPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..bc4deec643c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneIDPubSubTypes.h @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ProtectedZoneID.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + +} // 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 ~ProtectedZoneIDPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONEID_PUBSUBTYPES_H_ + 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..4d1e0b4c463 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadius.cxx @@ -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 ProtectedZoneRadius.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace ProtectedZoneRadius_Constants { + + +} // namespace ProtectedZoneRadius_Constants + + +ProtectedZoneRadius::ProtectedZoneRadius() +{ +} + +ProtectedZoneRadius::~ProtectedZoneRadius() +{ +} + +ProtectedZoneRadius::ProtectedZoneRadius( + const ProtectedZoneRadius& x) +{ + m_value = x.m_value; +} + +ProtectedZoneRadius::ProtectedZoneRadius( + ProtectedZoneRadius&& x) noexcept +{ + m_value = x.m_value; +} + +ProtectedZoneRadius& ProtectedZoneRadius::operator =( + const ProtectedZoneRadius& x) +{ + + m_value = x.m_value; + return *this; +} + +ProtectedZoneRadius& ProtectedZoneRadius::operator =( + ProtectedZoneRadius&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool ProtectedZoneRadius::operator ==( + const ProtectedZoneRadius& x) const +{ + return (m_value == x.m_value); +} + +bool ProtectedZoneRadius::operator !=( + const ProtectedZoneRadius& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void ProtectedZoneRadius::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t ProtectedZoneRadius::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& ProtectedZoneRadius::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ProtectedZoneRadiusCdrAux.ipp" + 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..f46d6d91307 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadius.h @@ -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 ProtectedZoneRadius.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusCdrAux.hpp new file mode 100644 index 00000000000..af5102aad35 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ProtectedZoneRadiusCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUSCDRAUX_HPP_ + +#include "ProtectedZoneRadius.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_ProtectedZoneRadius_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_ProtectedZoneRadius_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedZoneRadius& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusCdrAux.ipp new file mode 100644 index 00000000000..c14aad6359e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ProtectedZoneRadiusCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUSCDRAUX_IPP_ + +#include "ProtectedZoneRadiusCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::ProtectedZoneRadius& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedZoneRadius& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::ProtectedZoneRadius& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedZoneRadius& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUSCDRAUX_IPP_ + 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..24a24094455 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusPubSubTypes.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 ProtectedZoneRadiusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ProtectedZoneRadiusPubSubTypes.h" +#include "ProtectedZoneRadiusCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ProtectedZoneRadius::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_ProtectedZoneRadius_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ProtectedZoneRadiusPubSubType::~ProtectedZoneRadiusPubSubType() +{ +} + +bool ProtectedZoneRadiusPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ProtectedZoneRadiusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ProtectedZoneRadiusPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..0d3e9ca57e3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneRadiusPubSubTypes.h @@ -0,0 +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 ProtectedZoneRadiusPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ProtectedZoneRadius.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + +} // 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 ~ProtectedZoneRadiusPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONERADIUS_PUBSUBTYPES_H_ + 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..1a3c1ec4fe6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneType.cxx @@ -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 ProtectedZoneType.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace ProtectedZoneType_Constants { + + +} // namespace ProtectedZoneType_Constants + + +ProtectedZoneType::ProtectedZoneType() +{ +} + +ProtectedZoneType::~ProtectedZoneType() +{ +} + +ProtectedZoneType::ProtectedZoneType( + const ProtectedZoneType& x) +{ + m_value = x.m_value; +} + +ProtectedZoneType::ProtectedZoneType( + ProtectedZoneType&& x) noexcept +{ + m_value = x.m_value; +} + +ProtectedZoneType& ProtectedZoneType::operator =( + const ProtectedZoneType& x) +{ + + m_value = x.m_value; + return *this; +} + +ProtectedZoneType& ProtectedZoneType::operator =( + ProtectedZoneType&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool ProtectedZoneType::operator ==( + const ProtectedZoneType& x) const +{ + return (m_value == x.m_value); +} + +bool ProtectedZoneType::operator !=( + const ProtectedZoneType& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void ProtectedZoneType::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t ProtectedZoneType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& ProtectedZoneType::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ProtectedZoneTypeCdrAux.ipp" + 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..da8f20741e0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneType.h @@ -0,0 +1,175 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypeCdrAux.hpp new file mode 100644 index 00000000000..b81272d8efe --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypeCdrAux.hpp @@ -0,0 +1,55 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ProtectedZoneTypeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPECDRAUX_HPP_ + +#include "ProtectedZoneType.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_ProtectedZoneType_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_ProtectedZoneType_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedZoneType& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypeCdrAux.ipp new file mode 100644 index 00000000000..65a10f17490 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypeCdrAux.ipp @@ -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 ProtectedZoneTypeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPECDRAUX_IPP_ + +#include "ProtectedZoneTypeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::ProtectedZoneType& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedZoneType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::ProtectedZoneType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ProtectedZoneType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPECDRAUX_IPP_ + 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..9b3bcacd37d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypePubSubTypes.cxx @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ProtectedZoneTypePubSubTypes.h" +#include "ProtectedZoneTypeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ProtectedZoneType::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_ProtectedZoneType_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ProtectedZoneTypePubSubType::~ProtectedZoneTypePubSubType() +{ +} + +bool ProtectedZoneTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ProtectedZoneTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ProtectedZoneTypePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..05406f3877d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ProtectedZoneTypePubSubTypes.h @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ProtectedZoneType.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + +} // 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 ~ProtectedZoneTypePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PROTECTEDZONETYPE_PUBSUBTYPES_H_ + 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..13f6f208291 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivation.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 PtActivation.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +PtActivation::PtActivation() +{ +} + +PtActivation::~PtActivation() +{ +} + +PtActivation::PtActivation( + const PtActivation& x) +{ + m_pt_activation_type = x.m_pt_activation_type; + m_pt_activation_data = x.m_pt_activation_data; +} + +PtActivation::PtActivation( + PtActivation&& x) noexcept +{ + m_pt_activation_type = std::move(x.m_pt_activation_type); + m_pt_activation_data = std::move(x.m_pt_activation_data); +} + +PtActivation& 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; +} + +PtActivation& PtActivation::operator =( + PtActivation&& x) noexcept +{ + + 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 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 PtActivation::operator !=( + const PtActivation& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& PtActivation::pt_activation_data() +{ + return m_pt_activation_data; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PtActivationCdrAux.ipp" + 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..3682890dc18 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivation.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATION_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "PtActivationData.h" +#include "PtActivationType.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationCdrAux.hpp new file mode 100644 index 00000000000..47cbee0bbae --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PtActivationCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONCDRAUX_HPP_ + +#include "PtActivation.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_PtActivation_max_cdr_typesize {120UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_PtActivation_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PtActivation& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationCdrAux.ipp new file mode 100644 index 00000000000..69887d0f509 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PtActivationCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONCDRAUX_IPP_ + +#include "PtActivationCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::PtActivation& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.pt_activation_type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.pt_activation_data(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PtActivation& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.pt_activation_type() + << eprosima::fastcdr::MemberId(1) << data.pt_activation_data() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::PtActivation& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.pt_activation_type(); + break; + + case 1: + dcdr >> data.pt_activation_data(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PtActivation& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONCDRAUX_IPP_ + 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..7e4530b7531 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationData.cxx @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace PtActivationData_Constants { + + +} // namespace PtActivationData_Constants + + + + +PtActivationData::PtActivationData() +{ +} + +PtActivationData::~PtActivationData() +{ +} + +PtActivationData::PtActivationData( + const PtActivationData& x) +{ + m_value = x.m_value; +} + +PtActivationData::PtActivationData( + PtActivationData&& x) noexcept +{ + m_value = std::move(x.m_value); +} + +PtActivationData& PtActivationData::operator =( + const PtActivationData& x) +{ + + m_value = x.m_value; + return *this; +} + +PtActivationData& PtActivationData::operator =( + PtActivationData&& x) noexcept +{ + + m_value = std::move(x.m_value); + return *this; +} + +bool PtActivationData::operator ==( + const PtActivationData& x) const +{ + return (m_value == x.m_value); +} + +bool PtActivationData::operator !=( + const PtActivationData& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void 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 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& PtActivationData::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& PtActivationData::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PtActivationDataCdrAux.ipp" + 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..902c7e6b961 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationData.h @@ -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 PtActivationData.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_value; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATA_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataCdrAux.hpp new file mode 100644 index 00000000000..44fbe91c61e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PtActivationDataCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATACDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATACDRAUX_HPP_ + +#include "PtActivationData.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_PtActivationData_max_cdr_typesize {108UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_PtActivationData_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PtActivationData& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATACDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataCdrAux.ipp new file mode 100644 index 00000000000..c3470fbf078 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PtActivationDataCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATACDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATACDRAUX_IPP_ + +#include "PtActivationDataCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::PtActivationData& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PtActivationData& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::PtActivationData& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PtActivationData& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATACDRAUX_IPP_ + 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..4fe14a6bb1e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataPubSubTypes.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 PtActivationDataPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PtActivationDataPubSubTypes.h" +#include "PtActivationDataCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PtActivationData::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_PtActivationData_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PtActivationDataPubSubType::~PtActivationDataPubSubType() +{ +} + +bool PtActivationDataPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PtActivationDataPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PtActivationDataPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace etsi_its_cam_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataPubSubTypes.h new file mode 100644 index 00000000000..51f15c6b67f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationDataPubSubTypes.h @@ -0,0 +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 PtActivationDataPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "PtActivationData.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated PtActivationData 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 PtActivationData_Constants { + + + + +} // namespace PtActivationData_Constants + + + + + +/*! + * @brief This class represents the TopicDataType of the type PtActivationData defined by the user in the IDL file. + * @ingroup PtActivationData + */ +class PtActivationDataPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef PtActivationData type; + + eProsima_user_DllExport PtActivationDataPubSubType(); + + eProsima_user_DllExport ~PtActivationDataPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONDATA_PUBSUBTYPES_H_ + 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..6dfa7bc49fd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationPubSubTypes.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 PtActivationPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PtActivationPubSubTypes.h" +#include "PtActivationCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +PtActivationPubSubType::PtActivationPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::PtActivation_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PtActivation::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_PtActivation_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PtActivationPubSubType::~PtActivationPubSubType() +{ +} + +bool PtActivationPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PtActivationPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PtActivationPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..873a6da4568 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "PtActivation.h" + +#include "PtActivationDataPubSubTypes.h" +#include "PtActivationTypePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~PtActivationPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATION_PUBSUBTYPES_H_ + 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..d7c92466c73 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationType.cxx @@ -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 PtActivationType.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace PtActivationType_Constants { + + +} // namespace PtActivationType_Constants + + +PtActivationType::PtActivationType() +{ +} + +PtActivationType::~PtActivationType() +{ +} + +PtActivationType::PtActivationType( + const PtActivationType& x) +{ + m_value = x.m_value; +} + +PtActivationType::PtActivationType( + PtActivationType&& x) noexcept +{ + m_value = x.m_value; +} + +PtActivationType& PtActivationType::operator =( + const PtActivationType& x) +{ + + m_value = x.m_value; + return *this; +} + +PtActivationType& PtActivationType::operator =( + PtActivationType&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool PtActivationType::operator ==( + const PtActivationType& x) const +{ + return (m_value == x.m_value); +} + +bool PtActivationType::operator !=( + const PtActivationType& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void PtActivationType::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t PtActivationType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& PtActivationType::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PtActivationTypeCdrAux.ipp" + 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..f5af3a7cdd6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationType.h @@ -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 PtActivationType.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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 R09_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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypeCdrAux.hpp new file mode 100644 index 00000000000..574a08b7c81 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypeCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PtActivationTypeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPECDRAUX_HPP_ + +#include "PtActivationType.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_PtActivationType_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_PtActivationType_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PtActivationType& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypeCdrAux.ipp new file mode 100644 index 00000000000..a04973f1659 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypeCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PtActivationTypeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPECDRAUX_IPP_ + +#include "PtActivationTypeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::PtActivationType& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PtActivationType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::PtActivationType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PtActivationType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPECDRAUX_IPP_ + 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..c5d05257033 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PtActivationTypePubSubTypes.h" +#include "PtActivationTypeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PtActivationType::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_PtActivationType_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PtActivationTypePubSubType::~PtActivationTypePubSubType() +{ +} + +bool PtActivationTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PtActivationTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PtActivationTypePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..21136ec00fb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PtActivationTypePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "PtActivationType.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~PtActivationTypePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PTACTIVATIONTYPE_PUBSUBTYPES_H_ + 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..a970a4d70d2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainer.cxx @@ -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 PublicTransportContainer.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +PublicTransportContainer::PublicTransportContainer() +{ +} + +PublicTransportContainer::~PublicTransportContainer() +{ +} + +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; +} + +PublicTransportContainer::PublicTransportContainer( + PublicTransportContainer&& x) noexcept +{ + 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; +} + +PublicTransportContainer& 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; +} + +PublicTransportContainer& PublicTransportContainer::operator =( + PublicTransportContainer&& x) noexcept +{ + + 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 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 PublicTransportContainer::operator !=( + const PublicTransportContainer& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member embarkation_status + * @param _embarkation_status New value to be copied in member embarkation_status + */ +void 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 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& 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& 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 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 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& 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& 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 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 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& PublicTransportContainer::pt_activation_is_present() +{ + return m_pt_activation_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PublicTransportContainerCdrAux.ipp" + 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..c48ee0679b6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainer.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 PublicTransportContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "PtActivation.h" +#include "EmbarkationStatus.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINER_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerCdrAux.hpp new file mode 100644 index 00000000000..e803445cdd4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PublicTransportContainerCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINERCDRAUX_HPP_ + +#include "PublicTransportContainer.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_PublicTransportContainer_max_cdr_typesize {133UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_PublicTransportContainer_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PublicTransportContainer& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerCdrAux.ipp new file mode 100644 index 00000000000..d420704fc0a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PublicTransportContainerCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINERCDRAUX_IPP_ + +#include "PublicTransportContainerCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::PublicTransportContainer& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.embarkation_status(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.pt_activation(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.pt_activation_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PublicTransportContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.embarkation_status() + << eprosima::fastcdr::MemberId(1) << data.pt_activation() + << eprosima::fastcdr::MemberId(2) << data.pt_activation_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::PublicTransportContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.embarkation_status(); + break; + + case 1: + dcdr >> data.pt_activation(); + break; + + case 2: + dcdr >> data.pt_activation_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::PublicTransportContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINERCDRAUX_IPP_ + 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..089775a7589 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerPubSubTypes.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 PublicTransportContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PublicTransportContainerPubSubTypes.h" +#include "PublicTransportContainerCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +PublicTransportContainerPubSubType::PublicTransportContainerPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::PublicTransportContainer_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PublicTransportContainer::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_PublicTransportContainer_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PublicTransportContainerPubSubType::~PublicTransportContainerPubSubType() +{ +} + +bool PublicTransportContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PublicTransportContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PublicTransportContainerPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..5718dececb8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/PublicTransportContainerPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "PublicTransportContainer.h" + +#include "PtActivationPubSubTypes.h" +#include "EmbarkationStatusPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~PublicTransportContainerPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_PUBLICTRANSPORTCONTAINER_PUBSUBTYPES_H_ + 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..1a5d12bca42 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.cxx @@ -0,0 +1,175 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +RSUContainerHighFrequency::RSUContainerHighFrequency() +{ +} + +RSUContainerHighFrequency::~RSUContainerHighFrequency() +{ +} + +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; +} + +RSUContainerHighFrequency::RSUContainerHighFrequency( + RSUContainerHighFrequency&& x) noexcept +{ + 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; +} + +RSUContainerHighFrequency& 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; +} + +RSUContainerHighFrequency& RSUContainerHighFrequency::operator =( + RSUContainerHighFrequency&& x) noexcept +{ + + 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 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 RSUContainerHighFrequency::operator !=( + const RSUContainerHighFrequency& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& RSUContainerHighFrequency::protected_communication_zones_rsu_is_present() +{ + return m_protected_communication_zones_rsu_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "RSUContainerHighFrequencyCdrAux.ipp" + 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..f51dcaeb5c8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequency.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 RSUContainerHighFrequency.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCY_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCY_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "ProtectedCommunicationZonesRSU.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + etsi_its_cam_msgs::msg::ProtectedCommunicationZonesRSU m_protected_communication_zones_rsu; + bool m_protected_communication_zones_rsu_is_present{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCY_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyCdrAux.hpp new file mode 100644 index 00000000000..1777c41a050 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyCdrAux.hpp @@ -0,0 +1,54 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file RSUContainerHighFrequencyCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCYCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCYCDRAUX_HPP_ + +#include "RSUContainerHighFrequency.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_RSUContainerHighFrequency_max_cdr_typesize {6414UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_RSUContainerHighFrequency_max_key_cdr_typesize {0UL}; + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RSUContainerHighFrequency& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCYCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyCdrAux.ipp new file mode 100644 index 00000000000..7bcf1b47bdb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file RSUContainerHighFrequencyCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCYCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCYCDRAUX_IPP_ + +#include "RSUContainerHighFrequencyCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::RSUContainerHighFrequency& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.protected_communication_zones_rsu(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.protected_communication_zones_rsu_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RSUContainerHighFrequency& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.protected_communication_zones_rsu() + << eprosima::fastcdr::MemberId(1) << data.protected_communication_zones_rsu_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::RSUContainerHighFrequency& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.protected_communication_zones_rsu(); + break; + + case 1: + dcdr >> data.protected_communication_zones_rsu_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RSUContainerHighFrequency& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCYCDRAUX_IPP_ + 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..bf49f0e881c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyPubSubTypes.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 RSUContainerHighFrequencyPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "RSUContainerHighFrequencyPubSubTypes.h" +#include "RSUContainerHighFrequencyCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +RSUContainerHighFrequencyPubSubType::RSUContainerHighFrequencyPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::RSUContainerHighFrequency_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(RSUContainerHighFrequency::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_RSUContainerHighFrequency_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +RSUContainerHighFrequencyPubSubType::~RSUContainerHighFrequencyPubSubType() +{ +} + +bool RSUContainerHighFrequencyPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool RSUContainerHighFrequencyPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function RSUContainerHighFrequencyPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..0c3d8b1fb19 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RSUContainerHighFrequencyPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "RSUContainerHighFrequency.h" + +#include "ProtectedCommunicationZonesRSUPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~RSUContainerHighFrequencyPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RSUCONTAINERHIGHFREQUENCY_PUBSUBTYPES_H_ + 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..4a2ec66f310 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePosition.cxx @@ -0,0 +1,273 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +ReferencePosition::ReferencePosition() +{ +} + +ReferencePosition::~ReferencePosition() +{ +} + +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; +} + +ReferencePosition::ReferencePosition( + ReferencePosition&& x) noexcept +{ + 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); +} + +ReferencePosition& 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; +} + +ReferencePosition& ReferencePosition::operator =( + ReferencePosition&& x) noexcept +{ + + 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 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 ReferencePosition::operator !=( + const ReferencePosition& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member latitude + * @param _latitude New value to be copied in member latitude + */ +void 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& ReferencePosition::altitude() +{ + return m_altitude; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ReferencePositionCdrAux.ipp" + 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..d349d914ec8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePosition.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 ReferencePosition.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITION_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "Latitude.h" +#include "PosConfidenceEllipse.h" +#include "Longitude.h" +#include "Altitude.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionCdrAux.hpp new file mode 100644 index 00000000000..46b37c234a4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ReferencePositionCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITIONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITIONCDRAUX_HPP_ + +#include "ReferencePosition.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_ReferencePosition_max_cdr_typesize {65UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_ReferencePosition_max_key_cdr_typesize {0UL}; + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ReferencePosition& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITIONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionCdrAux.ipp new file mode 100644 index 00000000000..885023a3e0e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionCdrAux.ipp @@ -0,0 +1,154 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ReferencePositionCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITIONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITIONCDRAUX_IPP_ + +#include "ReferencePositionCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::ReferencePosition& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.latitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.longitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.position_confidence_ellipse(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.altitude(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ReferencePosition& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.latitude() + << eprosima::fastcdr::MemberId(1) << data.longitude() + << eprosima::fastcdr::MemberId(2) << data.position_confidence_ellipse() + << eprosima::fastcdr::MemberId(3) << data.altitude() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::ReferencePosition& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.latitude(); + break; + + case 1: + dcdr >> data.longitude(); + break; + + case 2: + dcdr >> data.position_confidence_ellipse(); + break; + + case 3: + dcdr >> data.altitude(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::ReferencePosition& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITIONCDRAUX_IPP_ + 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..ced2617785c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionPubSubTypes.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 ReferencePositionPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ReferencePositionPubSubTypes.h" +#include "ReferencePositionCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +ReferencePositionPubSubType::ReferencePositionPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::ReferencePosition_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(ReferencePosition::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_ReferencePosition_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ReferencePositionPubSubType::~ReferencePositionPubSubType() +{ +} + +bool ReferencePositionPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ReferencePositionPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ReferencePositionPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..375f9195fd6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/ReferencePositionPubSubTypes.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 ReferencePositionPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "ReferencePosition.h" + +#include "LatitudePubSubTypes.h" +#include "PosConfidenceEllipsePubSubTypes.h" +#include "LongitudePubSubTypes.h" +#include "AltitudePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~ReferencePositionPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_REFERENCEPOSITION_PUBSUBTYPES_H_ + 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..68e2d8d25da --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainer.cxx @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +RescueContainer::RescueContainer() +{ +} + +RescueContainer::~RescueContainer() +{ +} + +RescueContainer::RescueContainer( + const RescueContainer& x) +{ + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; +} + +RescueContainer::RescueContainer( + RescueContainer&& x) noexcept +{ + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); +} + +RescueContainer& RescueContainer::operator =( + const RescueContainer& x) +{ + + m_light_bar_siren_in_use = x.m_light_bar_siren_in_use; + return *this; +} + +RescueContainer& RescueContainer::operator =( + RescueContainer&& x) noexcept +{ + + m_light_bar_siren_in_use = std::move(x.m_light_bar_siren_in_use); + return *this; +} + +bool RescueContainer::operator ==( + const RescueContainer& x) const +{ + return (m_light_bar_siren_in_use == x.m_light_bar_siren_in_use); +} + +bool RescueContainer::operator !=( + const RescueContainer& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& RescueContainer::light_bar_siren_in_use() +{ + return m_light_bar_siren_in_use; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "RescueContainerCdrAux.ipp" + 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..9d997624d86 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainer.h @@ -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 RescueContainer.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "LightBarSirenInUse.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerCdrAux.hpp new file mode 100644 index 00000000000..70b865905f2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file RescueContainerCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINERCDRAUX_HPP_ + +#include "RescueContainer.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_RescueContainer_max_cdr_typesize {113UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_RescueContainer_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RescueContainer& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerCdrAux.ipp new file mode 100644 index 00000000000..846e1ae2908 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerCdrAux.ipp @@ -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 RescueContainerCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINERCDRAUX_IPP_ + +#include "RescueContainerCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::RescueContainer& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.light_bar_siren_in_use(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RescueContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.light_bar_siren_in_use() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::RescueContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.light_bar_siren_in_use(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RescueContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINERCDRAUX_IPP_ + 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..a82e1284bf0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerPubSubTypes.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 RescueContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "RescueContainerPubSubTypes.h" +#include "RescueContainerCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +RescueContainerPubSubType::RescueContainerPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::RescueContainer_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(RescueContainer::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_RescueContainer_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +RescueContainerPubSubType::~RescueContainerPubSubType() +{ +} + +bool RescueContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool RescueContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function RescueContainerPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..500027b147a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RescueContainerPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "RescueContainer.h" + +#include "LightBarSirenInUsePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~RescueContainerPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_RESCUECONTAINER_PUBSUBTYPES_H_ + 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..adc977f8cc5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.cxx @@ -0,0 +1,297 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +RoadWorksContainerBasic::RoadWorksContainerBasic() +{ +} + +RoadWorksContainerBasic::~RoadWorksContainerBasic() +{ +} + +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; +} + +RoadWorksContainerBasic::RoadWorksContainerBasic( + RoadWorksContainerBasic&& x) noexcept +{ + 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; +} + +RoadWorksContainerBasic& 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; +} + +RoadWorksContainerBasic& RoadWorksContainerBasic::operator =( + RoadWorksContainerBasic&& x) noexcept +{ + + 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 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 RoadWorksContainerBasic::operator !=( + const RoadWorksContainerBasic& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& RoadWorksContainerBasic::closed_lanes_is_present() +{ + return m_closed_lanes_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "RoadWorksContainerBasicCdrAux.ipp" + 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..126c9573e7b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasic.h @@ -0,0 +1,277 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASIC_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASIC_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "RoadworksSubCauseCode.h" +#include "ClosedLanes.h" +#include "LightBarSirenInUse.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + etsi_its_cam_msgs::msg::RoadworksSubCauseCode m_roadworks_sub_cause_code; + bool m_roadworks_sub_cause_code_is_present{false}; + 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{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASIC_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicCdrAux.hpp new file mode 100644 index 00000000000..7638d56ae64 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file RoadWorksContainerBasicCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASICCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASICCDRAUX_HPP_ + +#include "RoadWorksContainerBasic.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_RoadWorksContainerBasic_max_cdr_typesize {255UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_RoadWorksContainerBasic_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RoadWorksContainerBasic& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASICCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicCdrAux.ipp new file mode 100644 index 00000000000..ced5f3f37d3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicCdrAux.ipp @@ -0,0 +1,162 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file RoadWorksContainerBasicCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASICCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASICCDRAUX_IPP_ + +#include "RoadWorksContainerBasicCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::RoadWorksContainerBasic& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.roadworks_sub_cause_code(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.roadworks_sub_cause_code_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.light_bar_siren_in_use(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.closed_lanes(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.closed_lanes_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RoadWorksContainerBasic& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.roadworks_sub_cause_code() + << eprosima::fastcdr::MemberId(1) << data.roadworks_sub_cause_code_is_present() + << eprosima::fastcdr::MemberId(2) << data.light_bar_siren_in_use() + << eprosima::fastcdr::MemberId(3) << data.closed_lanes() + << eprosima::fastcdr::MemberId(4) << data.closed_lanes_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::RoadWorksContainerBasic& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.roadworks_sub_cause_code(); + break; + + case 1: + dcdr >> data.roadworks_sub_cause_code_is_present(); + break; + + case 2: + dcdr >> data.light_bar_siren_in_use(); + break; + + case 3: + dcdr >> data.closed_lanes(); + break; + + case 4: + dcdr >> data.closed_lanes_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RoadWorksContainerBasic& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASICCDRAUX_IPP_ + 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..51b934d446a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicPubSubTypes.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 RoadWorksContainerBasicPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "RoadWorksContainerBasicPubSubTypes.h" +#include "RoadWorksContainerBasicCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +RoadWorksContainerBasicPubSubType::RoadWorksContainerBasicPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::RoadWorksContainerBasic_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(RoadWorksContainerBasic::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_RoadWorksContainerBasic_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +RoadWorksContainerBasicPubSubType::~RoadWorksContainerBasicPubSubType() +{ +} + +bool RoadWorksContainerBasicPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool RoadWorksContainerBasicPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function RoadWorksContainerBasicPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..77ce78643c8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadWorksContainerBasicPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "RoadWorksContainerBasic.h" + +#include "RoadworksSubCauseCodePubSubTypes.h" +#include "ClosedLanesPubSubTypes.h" +#include "LightBarSirenInUsePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~RoadWorksContainerBasicPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSCONTAINERBASIC_PUBSUBTYPES_H_ + 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..b4bd64536b2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.cxx @@ -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 RoadworksSubCauseCode.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace RoadworksSubCauseCode_Constants { + + +} // namespace RoadworksSubCauseCode_Constants + + +RoadworksSubCauseCode::RoadworksSubCauseCode() +{ +} + +RoadworksSubCauseCode::~RoadworksSubCauseCode() +{ +} + +RoadworksSubCauseCode::RoadworksSubCauseCode( + const RoadworksSubCauseCode& x) +{ + m_value = x.m_value; +} + +RoadworksSubCauseCode::RoadworksSubCauseCode( + RoadworksSubCauseCode&& x) noexcept +{ + m_value = x.m_value; +} + +RoadworksSubCauseCode& RoadworksSubCauseCode::operator =( + const RoadworksSubCauseCode& x) +{ + + m_value = x.m_value; + return *this; +} + +RoadworksSubCauseCode& RoadworksSubCauseCode::operator =( + RoadworksSubCauseCode&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool RoadworksSubCauseCode::operator ==( + const RoadworksSubCauseCode& x) const +{ + return (m_value == x.m_value); +} + +bool RoadworksSubCauseCode::operator !=( + const RoadworksSubCauseCode& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void RoadworksSubCauseCode::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t RoadworksSubCauseCode::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& RoadworksSubCauseCode::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "RoadworksSubCauseCodeCdrAux.ipp" + 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..765e4ed1851 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCode.h @@ -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 RoadworksSubCauseCode.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodeCdrAux.hpp new file mode 100644 index 00000000000..8526cbcc029 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodeCdrAux.hpp @@ -0,0 +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 RoadworksSubCauseCodeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODECDRAUX_HPP_ + +#include "RoadworksSubCauseCode.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_RoadworksSubCauseCode_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_RoadworksSubCauseCode_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RoadworksSubCauseCode& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodeCdrAux.ipp new file mode 100644 index 00000000000..87ddbdeeaae --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodeCdrAux.ipp @@ -0,0 +1,149 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file RoadworksSubCauseCodeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODECDRAUX_IPP_ + +#include "RoadworksSubCauseCodeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::RoadworksSubCauseCode& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RoadworksSubCauseCode& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::RoadworksSubCauseCode& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::RoadworksSubCauseCode& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODECDRAUX_IPP_ + 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..7ce97e795c6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodePubSubTypes.cxx @@ -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 RoadworksSubCauseCodePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "RoadworksSubCauseCodePubSubTypes.h" +#include "RoadworksSubCauseCodeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(RoadworksSubCauseCode::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_RoadworksSubCauseCode_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +RoadworksSubCauseCodePubSubType::~RoadworksSubCauseCodePubSubType() +{ +} + +bool RoadworksSubCauseCodePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool RoadworksSubCauseCodePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function RoadworksSubCauseCodePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..ba1ad743091 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/RoadworksSubCauseCodePubSubTypes.h @@ -0,0 +1,155 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "RoadworksSubCauseCode.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + +} // 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 ~RoadworksSubCauseCodePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_ROADWORKSSUBCAUSECODE_PUBSUBTYPES_H_ + 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..7cf3f776566 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainer.cxx @@ -0,0 +1,375 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +SafetyCarContainer::SafetyCarContainer() +{ +} + +SafetyCarContainer::~SafetyCarContainer() +{ +} + +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; +} + +SafetyCarContainer::SafetyCarContainer( + SafetyCarContainer&& x) noexcept +{ + 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; +} + +SafetyCarContainer& 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; +} + +SafetyCarContainer& SafetyCarContainer::operator =( + SafetyCarContainer&& x) noexcept +{ + + 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 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 SafetyCarContainer::operator !=( + const SafetyCarContainer& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& 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 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 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& 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& 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 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 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& SafetyCarContainer::speed_limit_is_present() +{ + return m_speed_limit_is_present; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SafetyCarContainerCdrAux.ipp" + 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..a829a5dc9a0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainer.h @@ -0,0 +1,327 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "SpeedLimit.h" +#include "CauseCode.h" +#include "LightBarSirenInUse.h" +#include "TrafficRule.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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{false}; + etsi_its_cam_msgs::msg::TrafficRule m_traffic_rule; + bool m_traffic_rule_is_present{false}; + etsi_its_cam_msgs::msg::SpeedLimit m_speed_limit; + bool m_speed_limit_is_present{false}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINER_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerCdrAux.hpp new file mode 100644 index 00000000000..032a8fdc675 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerCdrAux.hpp @@ -0,0 +1,53 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SafetyCarContainerCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINERCDRAUX_HPP_ + +#include "SafetyCarContainer.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SafetyCarContainer_max_cdr_typesize {150UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SafetyCarContainer_max_key_cdr_typesize {0UL}; + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SafetyCarContainer& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerCdrAux.ipp new file mode 100644 index 00000000000..7379785f840 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerCdrAux.ipp @@ -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 SafetyCarContainerCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINERCDRAUX_IPP_ + +#include "SafetyCarContainerCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SafetyCarContainer& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.light_bar_siren_in_use(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.incident_indication(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.incident_indication_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.traffic_rule(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.traffic_rule_is_present(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.speed_limit(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.speed_limit_is_present(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SafetyCarContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.light_bar_siren_in_use() + << eprosima::fastcdr::MemberId(1) << data.incident_indication() + << eprosima::fastcdr::MemberId(2) << data.incident_indication_is_present() + << eprosima::fastcdr::MemberId(3) << data.traffic_rule() + << eprosima::fastcdr::MemberId(4) << data.traffic_rule_is_present() + << eprosima::fastcdr::MemberId(5) << data.speed_limit() + << eprosima::fastcdr::MemberId(6) << data.speed_limit_is_present() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SafetyCarContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.light_bar_siren_in_use(); + break; + + case 1: + dcdr >> data.incident_indication(); + break; + + case 2: + dcdr >> data.incident_indication_is_present(); + break; + + case 3: + dcdr >> data.traffic_rule(); + break; + + case 4: + dcdr >> data.traffic_rule_is_present(); + break; + + case 5: + dcdr >> data.speed_limit(); + break; + + case 6: + dcdr >> data.speed_limit_is_present(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SafetyCarContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINERCDRAUX_IPP_ + 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..3d1ab901105 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerPubSubTypes.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 SafetyCarContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SafetyCarContainerPubSubTypes.h" +#include "SafetyCarContainerCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +SafetyCarContainerPubSubType::SafetyCarContainerPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::SafetyCarContainer_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SafetyCarContainer::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SafetyCarContainer_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SafetyCarContainerPubSubType::~SafetyCarContainerPubSubType() +{ +} + +bool SafetyCarContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SafetyCarContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SafetyCarContainerPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..49d649f38ec --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SafetyCarContainerPubSubTypes.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 SafetyCarContainerPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SafetyCarContainer.h" + +#include "SpeedLimitPubSubTypes.h" +#include "CauseCodePubSubTypes.h" +#include "LightBarSirenInUsePubSubTypes.h" +#include "TrafficRulePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~SafetyCarContainerPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SAFETYCARCONTAINER_PUBSUBTYPES_H_ + 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..f5506857820 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLength.cxx @@ -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 SemiAxisLength.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace SemiAxisLength_Constants { + + +} // namespace SemiAxisLength_Constants + + +SemiAxisLength::SemiAxisLength() +{ +} + +SemiAxisLength::~SemiAxisLength() +{ +} + +SemiAxisLength::SemiAxisLength( + const SemiAxisLength& x) +{ + m_value = x.m_value; +} + +SemiAxisLength::SemiAxisLength( + SemiAxisLength&& x) noexcept +{ + m_value = x.m_value; +} + +SemiAxisLength& SemiAxisLength::operator =( + const SemiAxisLength& x) +{ + + m_value = x.m_value; + return *this; +} + +SemiAxisLength& SemiAxisLength::operator =( + SemiAxisLength&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool SemiAxisLength::operator ==( + const SemiAxisLength& x) const +{ + return (m_value == x.m_value); +} + +bool SemiAxisLength::operator !=( + const SemiAxisLength& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void SemiAxisLength::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t SemiAxisLength::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& SemiAxisLength::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SemiAxisLengthCdrAux.ipp" + 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..2d4714c65cd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLength.h @@ -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 SemiAxisLength.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTH_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthCdrAux.hpp new file mode 100644 index 00000000000..9b8d8b83a75 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SemiAxisLengthCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTHCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTHCDRAUX_HPP_ + +#include "SemiAxisLength.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SemiAxisLength_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SemiAxisLength_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SemiAxisLength& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTHCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthCdrAux.ipp new file mode 100644 index 00000000000..857a6cc8343 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SemiAxisLengthCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTHCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTHCDRAUX_IPP_ + +#include "SemiAxisLengthCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SemiAxisLength& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SemiAxisLength& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SemiAxisLength& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SemiAxisLength& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTHCDRAUX_IPP_ + 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..cd2ba3d6a05 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthPubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SemiAxisLengthPubSubTypes.h" +#include "SemiAxisLengthCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SemiAxisLength::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SemiAxisLength_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SemiAxisLengthPubSubType::~SemiAxisLengthPubSubType() +{ +} + +bool SemiAxisLengthPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SemiAxisLengthPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SemiAxisLengthPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..ce852ac1c53 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SemiAxisLengthPubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SemiAxisLength.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~SemiAxisLengthPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SEMIAXISLENGTH_PUBSUBTYPES_H_ + 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..22d94af4908 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainer.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 SpecialTransportContainer.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +SpecialTransportContainer::SpecialTransportContainer() +{ +} + +SpecialTransportContainer::~SpecialTransportContainer() +{ +} + +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; +} + +SpecialTransportContainer::SpecialTransportContainer( + SpecialTransportContainer&& x) noexcept +{ + 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); +} + +SpecialTransportContainer& 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; +} + +SpecialTransportContainer& SpecialTransportContainer::operator =( + SpecialTransportContainer&& x) noexcept +{ + + 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 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 SpecialTransportContainer::operator !=( + const SpecialTransportContainer& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& SpecialTransportContainer::light_bar_siren_in_use() +{ + return m_light_bar_siren_in_use; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SpecialTransportContainerCdrAux.ipp" + 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..3a62b40d2af --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainer.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "SpecialTransportType.h" +#include "LightBarSirenInUse.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerCdrAux.hpp new file mode 100644 index 00000000000..0ed6ff9942d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpecialTransportContainerCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINERCDRAUX_HPP_ + +#include "SpecialTransportContainer.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SpecialTransportContainer_max_cdr_typesize {225UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SpecialTransportContainer_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpecialTransportContainer& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerCdrAux.ipp new file mode 100644 index 00000000000..c3993c40925 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpecialTransportContainerCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINERCDRAUX_IPP_ + +#include "SpecialTransportContainerCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SpecialTransportContainer& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.special_transport_type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.light_bar_siren_in_use(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpecialTransportContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.special_transport_type() + << eprosima::fastcdr::MemberId(1) << data.light_bar_siren_in_use() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SpecialTransportContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.special_transport_type(); + break; + + case 1: + dcdr >> data.light_bar_siren_in_use(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpecialTransportContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINERCDRAUX_IPP_ + 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..97f98aa0020 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerPubSubTypes.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 SpecialTransportContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SpecialTransportContainerPubSubTypes.h" +#include "SpecialTransportContainerCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +SpecialTransportContainerPubSubType::SpecialTransportContainerPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::SpecialTransportContainer_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SpecialTransportContainer::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SpecialTransportContainer_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SpecialTransportContainerPubSubType::~SpecialTransportContainerPubSubType() +{ +} + +bool SpecialTransportContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SpecialTransportContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SpecialTransportContainerPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..32c06fc2fbb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportContainerPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SpecialTransportContainer.h" + +#include "SpecialTransportTypePubSubTypes.h" +#include "LightBarSirenInUsePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~SpecialTransportContainerPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTCONTAINER_PUBSUBTYPES_H_ + 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..be9633e1ccf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportType.cxx @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace SpecialTransportType_Constants { + + +} // namespace SpecialTransportType_Constants + + +SpecialTransportType::SpecialTransportType() +{ +} + +SpecialTransportType::~SpecialTransportType() +{ +} + +SpecialTransportType::SpecialTransportType( + const SpecialTransportType& x) +{ + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; +} + +SpecialTransportType::SpecialTransportType( + SpecialTransportType&& x) noexcept +{ + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; +} + +SpecialTransportType& SpecialTransportType::operator =( + const SpecialTransportType& x) +{ + + m_value = x.m_value; + m_bits_unused = x.m_bits_unused; + return *this; +} + +SpecialTransportType& SpecialTransportType::operator =( + SpecialTransportType&& x) noexcept +{ + + m_value = std::move(x.m_value); + m_bits_unused = x.m_bits_unused; + return *this; +} + +bool SpecialTransportType::operator ==( + const SpecialTransportType& x) const +{ + return (m_value == x.m_value && + m_bits_unused == x.m_bits_unused); +} + +bool SpecialTransportType::operator !=( + const SpecialTransportType& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member value + * @param _value New value to be copied in member value + */ +void 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 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& SpecialTransportType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +std::vector& 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 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 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& SpecialTransportType::bits_unused() +{ + return m_bits_unused; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SpecialTransportTypeCdrAux.ipp" + 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..cbf90945c1e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportType.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + std::vector m_value; + uint8_t m_bits_unused{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypeCdrAux.hpp new file mode 100644 index 00000000000..a4255e59181 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypeCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpecialTransportTypeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPECDRAUX_HPP_ + +#include "SpecialTransportType.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SpecialTransportType_max_cdr_typesize {109UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SpecialTransportType_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpecialTransportType& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypeCdrAux.ipp new file mode 100644 index 00000000000..03d6663e33f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypeCdrAux.ipp @@ -0,0 +1,149 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpecialTransportTypeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPECDRAUX_IPP_ + +#include "SpecialTransportTypeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SpecialTransportType& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.bits_unused(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpecialTransportType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() + << eprosima::fastcdr::MemberId(1) << data.bits_unused() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SpecialTransportType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + case 1: + dcdr >> data.bits_unused(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpecialTransportType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPECDRAUX_IPP_ + 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..28ed380ad13 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SpecialTransportTypePubSubTypes.h" +#include "SpecialTransportTypeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SpecialTransportType::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SpecialTransportType_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SpecialTransportTypePubSubType::~SpecialTransportTypePubSubType() +{ +} + +bool SpecialTransportTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SpecialTransportTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SpecialTransportTypePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..5fbc7fad7d8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialTransportTypePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SpecialTransportType.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~SpecialTransportTypePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALTRANSPORTTYPE_PUBSUBTYPES_H_ + 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..d775f32ed81 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainer.cxx @@ -0,0 +1,443 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace SpecialVehicleContainer_Constants { + + +} // namespace SpecialVehicleContainer_Constants + + +SpecialVehicleContainer::SpecialVehicleContainer() +{ +} + +SpecialVehicleContainer::~SpecialVehicleContainer() +{ +} + +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; +} + +SpecialVehicleContainer::SpecialVehicleContainer( + SpecialVehicleContainer&& x) noexcept +{ + 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); +} + +SpecialVehicleContainer& 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; +} + +SpecialVehicleContainer& SpecialVehicleContainer::operator =( + SpecialVehicleContainer&& x) noexcept +{ + + 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 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 SpecialVehicleContainer::operator !=( + const SpecialVehicleContainer& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member choice + * @param _choice New value for member choice + */ +void SpecialVehicleContainer::choice( + uint8_t _choice) +{ + m_choice = _choice; +} + +/*! + * @brief This function returns the value of member choice + * @return Value of member choice + */ +uint8_t SpecialVehicleContainer::choice() const +{ + return m_choice; +} + +/*! + * @brief This function returns a reference to member choice + * @return Reference to member choice + */ +uint8_t& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& 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 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 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& 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& SpecialVehicleContainer::safety_car_container() +{ + return m_safety_car_container; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SpecialVehicleContainerCdrAux.ipp" + 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..3ef2d734c86 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainer.h @@ -0,0 +1,383 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINER_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "PublicTransportContainer.h" +#include "DangerousGoodsContainer.h" +#include "RescueContainer.h" +#include "EmergencyContainer.h" +#include "RoadWorksContainerBasic.h" +#include "SafetyCarContainer.h" +#include "SpecialTransportContainer.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_choice{0}; + 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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerCdrAux.hpp new file mode 100644 index 00000000000..0a750527f6f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerCdrAux.hpp @@ -0,0 +1,87 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpecialVehicleContainerCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINERCDRAUX_HPP_ + +#include "SpecialVehicleContainer.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SpecialVehicleContainer_max_cdr_typesize {1154UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SpecialVehicleContainer_max_key_cdr_typesize {0UL}; + + + + + + + + + + + + + + + + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpecialVehicleContainer& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerCdrAux.ipp new file mode 100644 index 00000000000..1034d03330c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerCdrAux.ipp @@ -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 SpecialVehicleContainerCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINERCDRAUX_IPP_ + +#include "SpecialVehicleContainerCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SpecialVehicleContainer& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.choice(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.public_transport_container(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.special_transport_container(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.dangerous_goods_container(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.road_works_container_basic(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.rescue_container(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.emergency_container(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.safety_car_container(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpecialVehicleContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.choice() + << eprosima::fastcdr::MemberId(1) << data.public_transport_container() + << eprosima::fastcdr::MemberId(2) << data.special_transport_container() + << eprosima::fastcdr::MemberId(3) << data.dangerous_goods_container() + << eprosima::fastcdr::MemberId(4) << data.road_works_container_basic() + << eprosima::fastcdr::MemberId(5) << data.rescue_container() + << eprosima::fastcdr::MemberId(6) << data.emergency_container() + << eprosima::fastcdr::MemberId(7) << data.safety_car_container() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SpecialVehicleContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.choice(); + break; + + case 1: + dcdr >> data.public_transport_container(); + break; + + case 2: + dcdr >> data.special_transport_container(); + break; + + case 3: + dcdr >> data.dangerous_goods_container(); + break; + + case 4: + dcdr >> data.road_works_container_basic(); + break; + + case 5: + dcdr >> data.rescue_container(); + break; + + case 6: + dcdr >> data.emergency_container(); + break; + + case 7: + dcdr >> data.safety_car_container(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpecialVehicleContainer& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINERCDRAUX_IPP_ + 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..2dedb13f0e1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerPubSubTypes.cxx @@ -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 SpecialVehicleContainerPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SpecialVehicleContainerPubSubTypes.h" +#include "SpecialVehicleContainerCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SpecialVehicleContainer::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SpecialVehicleContainer_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SpecialVehicleContainerPubSubType::~SpecialVehicleContainerPubSubType() +{ +} + +bool SpecialVehicleContainerPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SpecialVehicleContainerPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SpecialVehicleContainerPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..260012c2999 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpecialVehicleContainerPubSubTypes.h @@ -0,0 +1,158 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SpecialVehicleContainer.h" + +#include "PublicTransportContainerPubSubTypes.h" +#include "DangerousGoodsContainerPubSubTypes.h" +#include "RescueContainerPubSubTypes.h" +#include "EmergencyContainerPubSubTypes.h" +#include "RoadWorksContainerBasicPubSubTypes.h" +#include "SafetyCarContainerPubSubTypes.h" +#include "SpecialTransportContainerPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + +} // 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 ~SpecialVehicleContainerPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPECIALVEHICLECONTAINER_PUBSUBTYPES_H_ + 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..acc2c1723c4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Speed.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 Speed.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +Speed::Speed() +{ +} + +Speed::~Speed() +{ +} + +Speed::Speed( + const Speed& x) +{ + m_speed_value = x.m_speed_value; + m_speed_confidence = x.m_speed_confidence; +} + +Speed::Speed( + Speed&& x) noexcept +{ + m_speed_value = std::move(x.m_speed_value); + m_speed_confidence = std::move(x.m_speed_confidence); +} + +Speed& Speed::operator =( + const Speed& x) +{ + + m_speed_value = x.m_speed_value; + m_speed_confidence = x.m_speed_confidence; + return *this; +} + +Speed& Speed::operator =( + Speed&& x) noexcept +{ + + m_speed_value = std::move(x.m_speed_value); + m_speed_confidence = std::move(x.m_speed_confidence); + return *this; +} + +bool Speed::operator ==( + const Speed& x) const +{ + return (m_speed_value == x.m_speed_value && + m_speed_confidence == x.m_speed_confidence); +} + +bool Speed::operator !=( + const Speed& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member speed_value + * @param _speed_value New value to be copied in member speed_value + */ +void 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 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& 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& 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 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 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& 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& Speed::speed_confidence() +{ + return m_speed_confidence; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SpeedCdrAux.ipp" + 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..be5bd8d6525 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/Speed.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEED_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEED_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "SpeedValue.h" +#include "SpeedConfidence.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedCdrAux.hpp new file mode 100644 index 00000000000..59803cabe71 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpeedCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCDRAUX_HPP_ + +#include "Speed.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_Speed_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_Speed_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Speed& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedCdrAux.ipp new file mode 100644 index 00000000000..2c6565575ed --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpeedCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCDRAUX_IPP_ + +#include "SpeedCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::Speed& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.speed_value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.speed_confidence(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Speed& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.speed_value() + << eprosima::fastcdr::MemberId(1) << data.speed_confidence() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::Speed& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.speed_value(); + break; + + case 1: + dcdr >> data.speed_confidence(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::Speed& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCDRAUX_IPP_ + 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..489a882171c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidence.cxx @@ -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 SpeedConfidence.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace SpeedConfidence_Constants { + + +} // namespace SpeedConfidence_Constants + + +SpeedConfidence::SpeedConfidence() +{ +} + +SpeedConfidence::~SpeedConfidence() +{ +} + +SpeedConfidence::SpeedConfidence( + const SpeedConfidence& x) +{ + m_value = x.m_value; +} + +SpeedConfidence::SpeedConfidence( + SpeedConfidence&& x) noexcept +{ + m_value = x.m_value; +} + +SpeedConfidence& SpeedConfidence::operator =( + const SpeedConfidence& x) +{ + + m_value = x.m_value; + return *this; +} + +SpeedConfidence& SpeedConfidence::operator =( + SpeedConfidence&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool SpeedConfidence::operator ==( + const SpeedConfidence& x) const +{ + return (m_value == x.m_value); +} + +bool SpeedConfidence::operator !=( + const SpeedConfidence& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void SpeedConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t SpeedConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& SpeedConfidence::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SpeedConfidenceCdrAux.ipp" + 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..6de0ba41bd8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidence.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidenceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidenceCdrAux.hpp new file mode 100644 index 00000000000..b4597e311f4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidenceCdrAux.hpp @@ -0,0 +1,63 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpeedConfidenceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCECDRAUX_HPP_ + +#include "SpeedConfidence.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SpeedConfidence_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SpeedConfidence_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpeedConfidence& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidenceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidenceCdrAux.ipp new file mode 100644 index 00000000000..49b77751115 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidenceCdrAux.ipp @@ -0,0 +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 SpeedConfidenceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCECDRAUX_IPP_ + +#include "SpeedConfidenceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SpeedConfidence& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpeedConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SpeedConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpeedConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCECDRAUX_IPP_ + 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..80be5398999 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidencePubSubTypes.cxx @@ -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 SpeedConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SpeedConfidencePubSubTypes.h" +#include "SpeedConfidenceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SpeedConfidence::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SpeedConfidence_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SpeedConfidencePubSubType::~SpeedConfidencePubSubType() +{ +} + +bool SpeedConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SpeedConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SpeedConfidencePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..13275d6eb0e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedConfidencePubSubTypes.h @@ -0,0 +1,149 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SpeedConfidence.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + +} // 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 ~SpeedConfidencePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDCONFIDENCE_PUBSUBTYPES_H_ + 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..3d1683bb032 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimit.cxx @@ -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 SpeedLimit.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace SpeedLimit_Constants { + + +} // namespace SpeedLimit_Constants + + +SpeedLimit::SpeedLimit() +{ +} + +SpeedLimit::~SpeedLimit() +{ +} + +SpeedLimit::SpeedLimit( + const SpeedLimit& x) +{ + m_value = x.m_value; +} + +SpeedLimit::SpeedLimit( + SpeedLimit&& x) noexcept +{ + m_value = x.m_value; +} + +SpeedLimit& SpeedLimit::operator =( + const SpeedLimit& x) +{ + + m_value = x.m_value; + return *this; +} + +SpeedLimit& SpeedLimit::operator =( + SpeedLimit&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool SpeedLimit::operator ==( + const SpeedLimit& x) const +{ + return (m_value == x.m_value); +} + +bool SpeedLimit::operator !=( + const SpeedLimit& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void SpeedLimit::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t SpeedLimit::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& SpeedLimit::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SpeedLimitCdrAux.ipp" + 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..45ad28629bd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimit.h @@ -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 SpeedLimit.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMIT_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitCdrAux.hpp new file mode 100644 index 00000000000..f82506a5190 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpeedLimitCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMITCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMITCDRAUX_HPP_ + +#include "SpeedLimit.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SpeedLimit_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SpeedLimit_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpeedLimit& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMITCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitCdrAux.ipp new file mode 100644 index 00000000000..c725604dc44 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitCdrAux.ipp @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpeedLimitCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMITCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMITCDRAUX_IPP_ + +#include "SpeedLimitCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SpeedLimit& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpeedLimit& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SpeedLimit& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpeedLimit& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMITCDRAUX_IPP_ + 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..7492afb9125 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitPubSubTypes.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 SpeedLimitPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SpeedLimitPubSubTypes.h" +#include "SpeedLimitCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SpeedLimit::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SpeedLimit_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SpeedLimitPubSubType::~SpeedLimitPubSubType() +{ +} + +bool SpeedLimitPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SpeedLimitPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SpeedLimitPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace etsi_its_cam_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitPubSubTypes.h new file mode 100644 index 00000000000..bc9cc3c5046 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedLimitPubSubTypes.h @@ -0,0 +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 SpeedLimitPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SpeedLimit.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated SpeedLimit 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 SpeedLimit_Constants { + + + + + + +} // namespace SpeedLimit_Constants + + + +/*! + * @brief This class represents the TopicDataType of the type SpeedLimit defined by the user in the IDL file. + * @ingroup SpeedLimit + */ +class SpeedLimitPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef SpeedLimit type; + + eProsima_user_DllExport SpeedLimitPubSubType(); + + eProsima_user_DllExport ~SpeedLimitPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDLIMIT_PUBSUBTYPES_H_ + 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..bcb01b15c2a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedPubSubTypes.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 SpeedPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SpeedPubSubTypes.h" +#include "SpeedCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +SpeedPubSubType::SpeedPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::Speed_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Speed::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_Speed_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SpeedPubSubType::~SpeedPubSubType() +{ +} + +bool SpeedPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SpeedPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SpeedPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..ed377528855 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "Speed.h" + +#include "SpeedValuePubSubTypes.h" +#include "SpeedConfidencePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~SpeedPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEED_PUBSUBTYPES_H_ + 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..a0ea77db534 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValue.cxx @@ -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 SpeedValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace SpeedValue_Constants { + + +} // namespace SpeedValue_Constants + + +SpeedValue::SpeedValue() +{ +} + +SpeedValue::~SpeedValue() +{ +} + +SpeedValue::SpeedValue( + const SpeedValue& x) +{ + m_value = x.m_value; +} + +SpeedValue::SpeedValue( + SpeedValue&& x) noexcept +{ + m_value = x.m_value; +} + +SpeedValue& SpeedValue::operator =( + const SpeedValue& x) +{ + + m_value = x.m_value; + return *this; +} + +SpeedValue& SpeedValue::operator =( + SpeedValue&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool SpeedValue::operator ==( + const SpeedValue& x) const +{ + return (m_value == x.m_value); +} + +bool SpeedValue::operator !=( + const SpeedValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void SpeedValue::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t SpeedValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& SpeedValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SpeedValueCdrAux.ipp" + 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..b7766f69d2a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValue.h @@ -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 SpeedValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValueCdrAux.hpp new file mode 100644 index 00000000000..5193283203d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValueCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpeedValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUECDRAUX_HPP_ + +#include "SpeedValue.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SpeedValue_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SpeedValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpeedValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValueCdrAux.ipp new file mode 100644 index 00000000000..c38925f10ea --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValueCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SpeedValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUECDRAUX_IPP_ + +#include "SpeedValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SpeedValue& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpeedValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SpeedValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SpeedValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUECDRAUX_IPP_ + 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..600d4194020 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValuePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SpeedValuePubSubTypes.h" +#include "SpeedValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SpeedValue::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SpeedValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SpeedValuePubSubType::~SpeedValuePubSubType() +{ +} + +bool SpeedValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SpeedValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SpeedValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..5f4788f633f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SpeedValuePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SpeedValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~SpeedValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SPEEDVALUE_PUBSUBTYPES_H_ + 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..93e7773f46e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationID.cxx @@ -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 StationID.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace StationID_Constants { + + +} // namespace StationID_Constants + + +StationID::StationID() +{ +} + +StationID::~StationID() +{ +} + +StationID::StationID( + const StationID& x) +{ + m_value = x.m_value; +} + +StationID::StationID( + StationID&& x) noexcept +{ + m_value = x.m_value; +} + +StationID& StationID::operator =( + const StationID& x) +{ + + m_value = x.m_value; + return *this; +} + +StationID& StationID::operator =( + StationID&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool StationID::operator ==( + const StationID& x) const +{ + return (m_value == x.m_value); +} + +bool StationID::operator !=( + const StationID& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void StationID::value( + uint32_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint32_t StationID::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint32_t& StationID::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "StationIDCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationID.h b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationID.h new file mode 100644 index 00000000000..6fad8ea8291 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationID.h @@ -0,0 +1,175 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 +#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(STATIONID_SOURCE) +#define STATIONID_DllAPI __declspec( dllexport ) +#else +#define STATIONID_DllAPI __declspec( dllimport ) +#endif // STATIONID_SOURCE +#else +#define STATIONID_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define STATIONID_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +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 StationID defined by the user in the IDL file. + * @ingroup StationID + */ +class StationID +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport StationID(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~StationID(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationID that will be copied. + */ + eProsima_user_DllExport StationID( + const StationID& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationID that will be copied. + */ + eProsima_user_DllExport StationID( + StationID&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationID that will be copied. + */ + eProsima_user_DllExport StationID& operator =( + const StationID& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object etsi_its_cam_msgs::msg::StationID that will be copied. + */ + eProsima_user_DllExport StationID& operator =( + StationID&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::StationID object to compare. + */ + eProsima_user_DllExport bool operator ==( + const StationID& x) const; + + /*! + * @brief Comparison operator. + * @param x etsi_its_cam_msgs::msg::StationID object to compare. + */ + eProsima_user_DllExport bool operator !=( + const StationID& 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(); + +private: + + uint32_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONID_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDCdrAux.hpp new file mode 100644 index 00000000000..a648da0e2b0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDCdrAux.hpp @@ -0,0 +1,55 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file StationIDCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONIDCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONIDCDRAUX_HPP_ + +#include "StationID.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_StationID_max_cdr_typesize {8UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_StationID_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::StationID& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONIDCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDCdrAux.ipp new file mode 100644 index 00000000000..f4378726852 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDCdrAux.ipp @@ -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 StationIDCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONIDCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONIDCDRAUX_IPP_ + +#include "StationIDCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::StationID& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::StationID& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::StationID& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::StationID& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONIDCDRAUX_IPP_ + 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..4417859eab4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDPubSubTypes.cxx @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "StationIDPubSubTypes.h" +#include "StationIDCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(StationID::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_StationID_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +StationIDPubSubType::~StationIDPubSubType() +{ +} + +bool StationIDPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool StationIDPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function StationIDPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..73289d28cc9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationIDPubSubTypes.h @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "StationID.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + +} // 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 ~StationIDPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONID_PUBSUBTYPES_H_ + 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..b10ffd98d77 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationType.cxx @@ -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 StationType.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace StationType_Constants { + + +} // namespace StationType_Constants + + +StationType::StationType() +{ +} + +StationType::~StationType() +{ +} + +StationType::StationType( + const StationType& x) +{ + m_value = x.m_value; +} + +StationType::StationType( + StationType&& x) noexcept +{ + m_value = x.m_value; +} + +StationType& StationType::operator =( + const StationType& x) +{ + + m_value = x.m_value; + return *this; +} + +StationType& StationType::operator =( + StationType&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool StationType::operator ==( + const StationType& x) const +{ + return (m_value == x.m_value); +} + +bool StationType::operator !=( + const StationType& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void StationType::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t StationType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& StationType::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "StationTypeCdrAux.ipp" + 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..cd7f06e2f95 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationType.h @@ -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 StationType.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypeCdrAux.hpp new file mode 100644 index 00000000000..568889c0f11 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypeCdrAux.hpp @@ -0,0 +1,81 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file StationTypeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPECDRAUX_HPP_ + +#include "StationType.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_StationType_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_StationType_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::StationType& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypeCdrAux.ipp new file mode 100644 index 00000000000..5d45354d15e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypeCdrAux.ipp @@ -0,0 +1,161 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file StationTypeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPECDRAUX_IPP_ + +#include "StationTypeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::StationType& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::StationType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::StationType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::StationType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPECDRAUX_IPP_ + 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..b29550c2a2e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypePubSubTypes.cxx @@ -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 StationTypePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "StationTypePubSubTypes.h" +#include "StationTypeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(StationType::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_StationType_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +StationTypePubSubType::~StationTypePubSubType() +{ +} + +bool StationTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool StationTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function StationTypePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..2ee587efe24 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/StationTypePubSubTypes.h @@ -0,0 +1,167 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "StationType.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~StationTypePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STATIONTYPE_PUBSUBTYPES_H_ + 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..853e5208828 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngle.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 SteeringWheelAngle.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +SteeringWheelAngle::SteeringWheelAngle() +{ +} + +SteeringWheelAngle::~SteeringWheelAngle() +{ +} + +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; +} + +SteeringWheelAngle::SteeringWheelAngle( + SteeringWheelAngle&& x) noexcept +{ + 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); +} + +SteeringWheelAngle& 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; +} + +SteeringWheelAngle& SteeringWheelAngle::operator =( + SteeringWheelAngle&& x) noexcept +{ + + 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 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 SteeringWheelAngle::operator !=( + const SteeringWheelAngle& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& SteeringWheelAngle::steering_wheel_angle_confidence() +{ + return m_steering_wheel_angle_confidence; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SteeringWheelAngleCdrAux.ipp" + 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..ba035957b36 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngle.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "SteeringWheelAngleConfidence.h" +#include "SteeringWheelAngleValue.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleCdrAux.hpp new file mode 100644 index 00000000000..d1efb84fd8f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SteeringWheelAngleCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECDRAUX_HPP_ + +#include "SteeringWheelAngle.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SteeringWheelAngle_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SteeringWheelAngle_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SteeringWheelAngle& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleCdrAux.ipp new file mode 100644 index 00000000000..09d62fcdd5f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SteeringWheelAngleCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECDRAUX_IPP_ + +#include "SteeringWheelAngleCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SteeringWheelAngle& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.steering_wheel_angle_value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.steering_wheel_angle_confidence(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SteeringWheelAngle& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.steering_wheel_angle_value() + << eprosima::fastcdr::MemberId(1) << data.steering_wheel_angle_confidence() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SteeringWheelAngle& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.steering_wheel_angle_value(); + break; + + case 1: + dcdr >> data.steering_wheel_angle_confidence(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SteeringWheelAngle& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECDRAUX_IPP_ + 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..8e1fc809160 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.cxx @@ -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 SteeringWheelAngleConfidence.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace SteeringWheelAngleConfidence_Constants { + + +} // namespace SteeringWheelAngleConfidence_Constants + + +SteeringWheelAngleConfidence::SteeringWheelAngleConfidence() +{ +} + +SteeringWheelAngleConfidence::~SteeringWheelAngleConfidence() +{ +} + +SteeringWheelAngleConfidence::SteeringWheelAngleConfidence( + const SteeringWheelAngleConfidence& x) +{ + m_value = x.m_value; +} + +SteeringWheelAngleConfidence::SteeringWheelAngleConfidence( + SteeringWheelAngleConfidence&& x) noexcept +{ + m_value = x.m_value; +} + +SteeringWheelAngleConfidence& SteeringWheelAngleConfidence::operator =( + const SteeringWheelAngleConfidence& x) +{ + + m_value = x.m_value; + return *this; +} + +SteeringWheelAngleConfidence& SteeringWheelAngleConfidence::operator =( + SteeringWheelAngleConfidence&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool SteeringWheelAngleConfidence::operator ==( + const SteeringWheelAngleConfidence& x) const +{ + return (m_value == x.m_value); +} + +bool SteeringWheelAngleConfidence::operator !=( + const SteeringWheelAngleConfidence& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void SteeringWheelAngleConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t SteeringWheelAngleConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& SteeringWheelAngleConfidence::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SteeringWheelAngleConfidenceCdrAux.ipp" + 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..eb6edad6f3d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidence.h @@ -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 SteeringWheelAngleConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidenceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidenceCdrAux.hpp new file mode 100644 index 00000000000..c82ddca8a06 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidenceCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SteeringWheelAngleConfidenceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCECDRAUX_HPP_ + +#include "SteeringWheelAngleConfidence.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SteeringWheelAngleConfidence_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SteeringWheelAngleConfidence_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidenceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidenceCdrAux.ipp new file mode 100644 index 00000000000..356e7939dac --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidenceCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SteeringWheelAngleConfidenceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCECDRAUX_IPP_ + +#include "SteeringWheelAngleConfidenceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SteeringWheelAngleConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCECDRAUX_IPP_ + 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..447bee931b8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidencePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SteeringWheelAngleConfidencePubSubTypes.h" +#include "SteeringWheelAngleConfidenceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SteeringWheelAngleConfidence::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SteeringWheelAngleConfidence_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SteeringWheelAngleConfidencePubSubType::~SteeringWheelAngleConfidencePubSubType() +{ +} + +bool SteeringWheelAngleConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SteeringWheelAngleConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SteeringWheelAngleConfidencePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..af65791d08c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleConfidencePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SteeringWheelAngleConfidence.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~SteeringWheelAngleConfidencePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLECONFIDENCE_PUBSUBTYPES_H_ + 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..10b4d7d76ea --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAnglePubSubTypes.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 SteeringWheelAnglePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SteeringWheelAnglePubSubTypes.h" +#include "SteeringWheelAngleCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +SteeringWheelAnglePubSubType::SteeringWheelAnglePubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::SteeringWheelAngle_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SteeringWheelAngle::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SteeringWheelAngle_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SteeringWheelAnglePubSubType::~SteeringWheelAnglePubSubType() +{ +} + +bool SteeringWheelAnglePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SteeringWheelAnglePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SteeringWheelAnglePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..5eb7a6cfd23 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAnglePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SteeringWheelAngle.h" + +#include "SteeringWheelAngleConfidencePubSubTypes.h" +#include "SteeringWheelAngleValuePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~SteeringWheelAnglePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLE_PUBSUBTYPES_H_ + 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..3b19faafb47 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.cxx @@ -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 SteeringWheelAngleValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace SteeringWheelAngleValue_Constants { + + +} // namespace SteeringWheelAngleValue_Constants + + +SteeringWheelAngleValue::SteeringWheelAngleValue() +{ +} + +SteeringWheelAngleValue::~SteeringWheelAngleValue() +{ +} + +SteeringWheelAngleValue::SteeringWheelAngleValue( + const SteeringWheelAngleValue& x) +{ + m_value = x.m_value; +} + +SteeringWheelAngleValue::SteeringWheelAngleValue( + SteeringWheelAngleValue&& x) noexcept +{ + m_value = x.m_value; +} + +SteeringWheelAngleValue& SteeringWheelAngleValue::operator =( + const SteeringWheelAngleValue& x) +{ + + m_value = x.m_value; + return *this; +} + +SteeringWheelAngleValue& SteeringWheelAngleValue::operator =( + SteeringWheelAngleValue&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool SteeringWheelAngleValue::operator ==( + const SteeringWheelAngleValue& x) const +{ + return (m_value == x.m_value); +} + +bool SteeringWheelAngleValue::operator !=( + const SteeringWheelAngleValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void SteeringWheelAngleValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t SteeringWheelAngleValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& SteeringWheelAngleValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SteeringWheelAngleValueCdrAux.ipp" + 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..35cc4da8778 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValue.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValueCdrAux.hpp new file mode 100644 index 00000000000..337e9e776d7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValueCdrAux.hpp @@ -0,0 +1,63 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SteeringWheelAngleValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUECDRAUX_HPP_ + +#include "SteeringWheelAngleValue.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SteeringWheelAngleValue_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SteeringWheelAngleValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SteeringWheelAngleValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValueCdrAux.ipp new file mode 100644 index 00000000000..b0b5d91ddf6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValueCdrAux.ipp @@ -0,0 +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 SteeringWheelAngleValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUECDRAUX_IPP_ + +#include "SteeringWheelAngleValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SteeringWheelAngleValue& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SteeringWheelAngleValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SteeringWheelAngleValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SteeringWheelAngleValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUECDRAUX_IPP_ + 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..6d5072986d7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValuePubSubTypes.cxx @@ -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 SteeringWheelAngleValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SteeringWheelAngleValuePubSubTypes.h" +#include "SteeringWheelAngleValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SteeringWheelAngleValue::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SteeringWheelAngleValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SteeringWheelAngleValuePubSubType::~SteeringWheelAngleValuePubSubType() +{ +} + +bool SteeringWheelAngleValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SteeringWheelAngleValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SteeringWheelAngleValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..ad022d99491 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SteeringWheelAngleValuePubSubTypes.h @@ -0,0 +1,149 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SteeringWheelAngleValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + +} // 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 ~SteeringWheelAngleValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_STEERINGWHEELANGLEVALUE_PUBSUBTYPES_H_ + 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..3c9e0fdbb74 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeType.cxx @@ -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 SubCauseCodeType.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace SubCauseCodeType_Constants { + + +} // namespace SubCauseCodeType_Constants + + +SubCauseCodeType::SubCauseCodeType() +{ +} + +SubCauseCodeType::~SubCauseCodeType() +{ +} + +SubCauseCodeType::SubCauseCodeType( + const SubCauseCodeType& x) +{ + m_value = x.m_value; +} + +SubCauseCodeType::SubCauseCodeType( + SubCauseCodeType&& x) noexcept +{ + m_value = x.m_value; +} + +SubCauseCodeType& SubCauseCodeType::operator =( + const SubCauseCodeType& x) +{ + + m_value = x.m_value; + return *this; +} + +SubCauseCodeType& SubCauseCodeType::operator =( + SubCauseCodeType&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool SubCauseCodeType::operator ==( + const SubCauseCodeType& x) const +{ + return (m_value == x.m_value); +} + +bool SubCauseCodeType::operator !=( + const SubCauseCodeType& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void SubCauseCodeType::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t SubCauseCodeType::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& SubCauseCodeType::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SubCauseCodeTypeCdrAux.ipp" + 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..6ab0c7c2e5a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeType.h @@ -0,0 +1,175 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypeCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypeCdrAux.hpp new file mode 100644 index 00000000000..9f56b507eea --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypeCdrAux.hpp @@ -0,0 +1,55 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SubCauseCodeTypeCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPECDRAUX_HPP_ + +#include "SubCauseCodeType.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_SubCauseCodeType_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_SubCauseCodeType_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SubCauseCodeType& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypeCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypeCdrAux.ipp new file mode 100644 index 00000000000..bb58a0cea10 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypeCdrAux.ipp @@ -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 SubCauseCodeTypeCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPECDRAUX_IPP_ + +#include "SubCauseCodeTypeCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::SubCauseCodeType& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SubCauseCodeType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::SubCauseCodeType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::SubCauseCodeType& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPECDRAUX_IPP_ + 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..2a6fa60f283 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypePubSubTypes.cxx @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SubCauseCodeTypePubSubTypes.h" +#include "SubCauseCodeTypeCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SubCauseCodeType::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_SubCauseCodeType_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SubCauseCodeTypePubSubType::~SubCauseCodeTypePubSubType() +{ +} + +bool SubCauseCodeTypePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SubCauseCodeTypePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SubCauseCodeTypePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..76719bf93a1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/SubCauseCodeTypePubSubTypes.h @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "SubCauseCodeType.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + +} // 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 ~SubCauseCodeTypePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_SUBCAUSECODETYPE_PUBSUBTYPES_H_ + 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..b97c317a8ca --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampIts.cxx @@ -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 TimestampIts.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace TimestampIts_Constants { + + +} // namespace TimestampIts_Constants + + +TimestampIts::TimestampIts() +{ +} + +TimestampIts::~TimestampIts() +{ +} + +TimestampIts::TimestampIts( + const TimestampIts& x) +{ + m_value = x.m_value; +} + +TimestampIts::TimestampIts( + TimestampIts&& x) noexcept +{ + m_value = x.m_value; +} + +TimestampIts& TimestampIts::operator =( + const TimestampIts& x) +{ + + m_value = x.m_value; + return *this; +} + +TimestampIts& TimestampIts::operator =( + TimestampIts&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool TimestampIts::operator ==( + const TimestampIts& x) const +{ + return (m_value == x.m_value); +} + +bool TimestampIts::operator !=( + const TimestampIts& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void TimestampIts::value( + uint64_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint64_t TimestampIts::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint64_t& TimestampIts::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "TimestampItsCdrAux.ipp" + 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..cbcbd15eac9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampIts.h @@ -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 TimestampIts.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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_OF2004 = 0; +const uint64_t ONE_MILLISEC_AFTER_UTC_START_OF2004 = 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint64_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsCdrAux.hpp new file mode 100644 index 00000000000..4d103faabeb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsCdrAux.hpp @@ -0,0 +1,59 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TimestampItsCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITSCDRAUX_HPP_ + +#include "TimestampIts.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_TimestampIts_max_cdr_typesize {16UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_TimestampIts_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::TimestampIts& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsCdrAux.ipp new file mode 100644 index 00000000000..e2ed317c638 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsCdrAux.ipp @@ -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 TimestampItsCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITSCDRAUX_IPP_ + +#include "TimestampItsCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::TimestampIts& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::TimestampIts& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::TimestampIts& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::TimestampIts& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITSCDRAUX_IPP_ + 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..d5411d02b2f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsPubSubTypes.cxx @@ -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 TimestampItsPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "TimestampItsPubSubTypes.h" +#include "TimestampItsCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(TimestampIts::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_TimestampIts_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +TimestampItsPubSubType::~TimestampItsPubSubType() +{ +} + +bool TimestampItsPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool TimestampItsPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function TimestampItsPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..c9494fa4270 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TimestampItsPubSubTypes.h @@ -0,0 +1,145 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "TimestampIts.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + +} // 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 ~TimestampItsPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TIMESTAMPITS_PUBSUBTYPES_H_ + 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..68b8fb683db --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRule.cxx @@ -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 TrafficRule.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace TrafficRule_Constants { + + +} // namespace TrafficRule_Constants + + +TrafficRule::TrafficRule() +{ +} + +TrafficRule::~TrafficRule() +{ +} + +TrafficRule::TrafficRule( + const TrafficRule& x) +{ + m_value = x.m_value; +} + +TrafficRule::TrafficRule( + TrafficRule&& x) noexcept +{ + m_value = x.m_value; +} + +TrafficRule& TrafficRule::operator =( + const TrafficRule& x) +{ + + m_value = x.m_value; + return *this; +} + +TrafficRule& TrafficRule::operator =( + TrafficRule&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool TrafficRule::operator ==( + const TrafficRule& x) const +{ + return (m_value == x.m_value); +} + +bool TrafficRule::operator !=( + const TrafficRule& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void TrafficRule::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t TrafficRule::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& TrafficRule::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "TrafficRuleCdrAux.ipp" + 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..345d1b3dcc1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRule.h @@ -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 TrafficRule.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRuleCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRuleCdrAux.hpp new file mode 100644 index 00000000000..32816ea8a7a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRuleCdrAux.hpp @@ -0,0 +1,59 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TrafficRuleCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULECDRAUX_HPP_ + +#include "TrafficRule.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_TrafficRule_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_TrafficRule_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::TrafficRule& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRuleCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRuleCdrAux.ipp new file mode 100644 index 00000000000..5c1036bde47 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRuleCdrAux.ipp @@ -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 TrafficRuleCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULECDRAUX_IPP_ + +#include "TrafficRuleCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::TrafficRule& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::TrafficRule& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::TrafficRule& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::TrafficRule& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULECDRAUX_IPP_ + 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..38625ec62ee --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRulePubSubTypes.cxx @@ -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 TrafficRulePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "TrafficRulePubSubTypes.h" +#include "TrafficRuleCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(TrafficRule::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_TrafficRule_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +TrafficRulePubSubType::~TrafficRulePubSubType() +{ +} + +bool TrafficRulePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool TrafficRulePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function TrafficRulePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..4704e3f8b07 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/TrafficRulePubSubTypes.h @@ -0,0 +1,145 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "TrafficRule.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + +} // 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 ~TrafficRulePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_TRAFFICRULE_PUBSUBTYPES_H_ + 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..07dd1d23510 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLength.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 VehicleLength.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +VehicleLength::VehicleLength() +{ +} + +VehicleLength::~VehicleLength() +{ +} + +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; +} + +VehicleLength::VehicleLength( + VehicleLength&& x) noexcept +{ + m_vehicle_length_value = std::move(x.m_vehicle_length_value); + m_vehicle_length_confidence_indication = std::move(x.m_vehicle_length_confidence_indication); +} + +VehicleLength& 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; +} + +VehicleLength& VehicleLength::operator =( + VehicleLength&& x) noexcept +{ + + 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 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 VehicleLength::operator !=( + const VehicleLength& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& VehicleLength::vehicle_length_confidence_indication() +{ + return m_vehicle_length_confidence_indication; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "VehicleLengthCdrAux.ipp" + 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..a8a35ec421d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLength.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTH_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTH_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "VehicleLengthValue.h" +#include "VehicleLengthConfidenceIndication.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthCdrAux.hpp new file mode 100644 index 00000000000..fc18006a78e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VehicleLengthCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCDRAUX_HPP_ + +#include "VehicleLength.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_VehicleLength_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_VehicleLength_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleLength& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthCdrAux.ipp new file mode 100644 index 00000000000..fb92c591d5f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VehicleLengthCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCDRAUX_IPP_ + +#include "VehicleLengthCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::VehicleLength& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.vehicle_length_value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.vehicle_length_confidence_indication(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleLength& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.vehicle_length_value() + << eprosima::fastcdr::MemberId(1) << data.vehicle_length_confidence_indication() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::VehicleLength& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.vehicle_length_value(); + break; + + case 1: + dcdr >> data.vehicle_length_confidence_indication(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleLength& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCDRAUX_IPP_ + 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..5a9a6dfcf1f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.cxx @@ -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 VehicleLengthConfidenceIndication.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace VehicleLengthConfidenceIndication_Constants { + + +} // namespace VehicleLengthConfidenceIndication_Constants + + +VehicleLengthConfidenceIndication::VehicleLengthConfidenceIndication() +{ +} + +VehicleLengthConfidenceIndication::~VehicleLengthConfidenceIndication() +{ +} + +VehicleLengthConfidenceIndication::VehicleLengthConfidenceIndication( + const VehicleLengthConfidenceIndication& x) +{ + m_value = x.m_value; +} + +VehicleLengthConfidenceIndication::VehicleLengthConfidenceIndication( + VehicleLengthConfidenceIndication&& x) noexcept +{ + m_value = x.m_value; +} + +VehicleLengthConfidenceIndication& VehicleLengthConfidenceIndication::operator =( + const VehicleLengthConfidenceIndication& x) +{ + + m_value = x.m_value; + return *this; +} + +VehicleLengthConfidenceIndication& VehicleLengthConfidenceIndication::operator =( + VehicleLengthConfidenceIndication&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool VehicleLengthConfidenceIndication::operator ==( + const VehicleLengthConfidenceIndication& x) const +{ + return (m_value == x.m_value); +} + +bool VehicleLengthConfidenceIndication::operator !=( + const VehicleLengthConfidenceIndication& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void VehicleLengthConfidenceIndication::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t VehicleLengthConfidenceIndication::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& VehicleLengthConfidenceIndication::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "VehicleLengthConfidenceIndicationCdrAux.ipp" + 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..badb41a8501 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndication.h @@ -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 VehicleLengthConfidenceIndication.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATION_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationCdrAux.hpp new file mode 100644 index 00000000000..95a59117e8b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VehicleLengthConfidenceIndicationCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATIONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATIONCDRAUX_HPP_ + +#include "VehicleLengthConfidenceIndication.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_VehicleLengthConfidenceIndication_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_VehicleLengthConfidenceIndication_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATIONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationCdrAux.ipp new file mode 100644 index 00000000000..da4eae444e1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VehicleLengthConfidenceIndicationCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATIONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATIONCDRAUX_IPP_ + +#include "VehicleLengthConfidenceIndicationCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleLengthConfidenceIndication& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATIONCDRAUX_IPP_ + 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..b4cec45cc28 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationPubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "VehicleLengthConfidenceIndicationPubSubTypes.h" +#include "VehicleLengthConfidenceIndicationCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(VehicleLengthConfidenceIndication::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_VehicleLengthConfidenceIndication_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +VehicleLengthConfidenceIndicationPubSubType::~VehicleLengthConfidenceIndicationPubSubType() +{ +} + +bool VehicleLengthConfidenceIndicationPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool VehicleLengthConfidenceIndicationPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function VehicleLengthConfidenceIndicationPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..0d27713a69a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthConfidenceIndicationPubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "VehicleLengthConfidenceIndication.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~VehicleLengthConfidenceIndicationPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHCONFIDENCEINDICATION_PUBSUBTYPES_H_ + 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..51a7762d0fa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthPubSubTypes.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 VehicleLengthPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "VehicleLengthPubSubTypes.h" +#include "VehicleLengthCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +VehicleLengthPubSubType::VehicleLengthPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::VehicleLength_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(VehicleLength::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_VehicleLength_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +VehicleLengthPubSubType::~VehicleLengthPubSubType() +{ +} + +bool VehicleLengthPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool VehicleLengthPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function VehicleLengthPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..b50c950f09e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "VehicleLength.h" + +#include "VehicleLengthValuePubSubTypes.h" +#include "VehicleLengthConfidenceIndicationPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~VehicleLengthPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTH_PUBSUBTYPES_H_ + 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..eb78bffd206 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValue.cxx @@ -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 VehicleLengthValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace VehicleLengthValue_Constants { + + +} // namespace VehicleLengthValue_Constants + + +VehicleLengthValue::VehicleLengthValue() +{ +} + +VehicleLengthValue::~VehicleLengthValue() +{ +} + +VehicleLengthValue::VehicleLengthValue( + const VehicleLengthValue& x) +{ + m_value = x.m_value; +} + +VehicleLengthValue::VehicleLengthValue( + VehicleLengthValue&& x) noexcept +{ + m_value = x.m_value; +} + +VehicleLengthValue& VehicleLengthValue::operator =( + const VehicleLengthValue& x) +{ + + m_value = x.m_value; + return *this; +} + +VehicleLengthValue& VehicleLengthValue::operator =( + VehicleLengthValue&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool VehicleLengthValue::operator ==( + const VehicleLengthValue& x) const +{ + return (m_value == x.m_value); +} + +bool VehicleLengthValue::operator !=( + const VehicleLengthValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void VehicleLengthValue::value( + uint16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint16_t VehicleLengthValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint16_t& VehicleLengthValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "VehicleLengthValueCdrAux.ipp" + 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..c5a838c00fe --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValue.h @@ -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 VehicleLengthValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValueCdrAux.hpp new file mode 100644 index 00000000000..0f953afc930 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValueCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VehicleLengthValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUECDRAUX_HPP_ + +#include "VehicleLengthValue.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_VehicleLengthValue_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_VehicleLengthValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleLengthValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValueCdrAux.ipp new file mode 100644 index 00000000000..e84ce535c00 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValueCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VehicleLengthValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUECDRAUX_IPP_ + +#include "VehicleLengthValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::VehicleLengthValue& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleLengthValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::VehicleLengthValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleLengthValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUECDRAUX_IPP_ + 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..fd846bb1cdd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValuePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "VehicleLengthValuePubSubTypes.h" +#include "VehicleLengthValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(VehicleLengthValue::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_VehicleLengthValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +VehicleLengthValuePubSubType::~VehicleLengthValuePubSubType() +{ +} + +bool VehicleLengthValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool VehicleLengthValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function VehicleLengthValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..cf41c772d19 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleLengthValuePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "VehicleLengthValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~VehicleLengthValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLELENGTHVALUE_PUBSUBTYPES_H_ + 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..e806ede9d14 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRole.cxx @@ -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 VehicleRole.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace VehicleRole_Constants { + + +} // namespace VehicleRole_Constants + + +VehicleRole::VehicleRole() +{ +} + +VehicleRole::~VehicleRole() +{ +} + +VehicleRole::VehicleRole( + const VehicleRole& x) +{ + m_value = x.m_value; +} + +VehicleRole::VehicleRole( + VehicleRole&& x) noexcept +{ + m_value = x.m_value; +} + +VehicleRole& VehicleRole::operator =( + const VehicleRole& x) +{ + + m_value = x.m_value; + return *this; +} + +VehicleRole& VehicleRole::operator =( + VehicleRole&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool VehicleRole::operator ==( + const VehicleRole& x) const +{ + return (m_value == x.m_value); +} + +bool VehicleRole::operator !=( + const VehicleRole& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void VehicleRole::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t VehicleRole::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& VehicleRole::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "VehicleRoleCdrAux.ipp" + 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..487f7ce609c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRole.h @@ -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 VehicleRole.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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 RESERVED1 = 13; +const uint8_t RESERVED2 = 14; +const uint8_t RESERVED3 = 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRoleCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRoleCdrAux.hpp new file mode 100644 index 00000000000..2c896a94b36 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRoleCdrAux.hpp @@ -0,0 +1,83 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VehicleRoleCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLECDRAUX_HPP_ + +#include "VehicleRole.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_VehicleRole_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_VehicleRole_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleRole& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRoleCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRoleCdrAux.ipp new file mode 100644 index 00000000000..aa9bae62445 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRoleCdrAux.ipp @@ -0,0 +1,163 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VehicleRoleCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLECDRAUX_IPP_ + +#include "VehicleRoleCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::VehicleRole& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleRole& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::VehicleRole& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleRole& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLECDRAUX_IPP_ + 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..e7fe4dc755a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRolePubSubTypes.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 VehicleRolePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "VehicleRolePubSubTypes.h" +#include "VehicleRoleCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(VehicleRole::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_VehicleRole_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +VehicleRolePubSubType::~VehicleRolePubSubType() +{ +} + +bool VehicleRolePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool VehicleRolePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function VehicleRolePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..6db539edf26 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleRolePubSubTypes.h @@ -0,0 +1,169 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "VehicleRole.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~VehicleRolePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEROLE_PUBSUBTYPES_H_ + 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..d2f60e9576d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidth.cxx @@ -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 VehicleWidth.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace VehicleWidth_Constants { + + +} // namespace VehicleWidth_Constants + + +VehicleWidth::VehicleWidth() +{ +} + +VehicleWidth::~VehicleWidth() +{ +} + +VehicleWidth::VehicleWidth( + const VehicleWidth& x) +{ + m_value = x.m_value; +} + +VehicleWidth::VehicleWidth( + VehicleWidth&& x) noexcept +{ + m_value = x.m_value; +} + +VehicleWidth& VehicleWidth::operator =( + const VehicleWidth& x) +{ + + m_value = x.m_value; + return *this; +} + +VehicleWidth& VehicleWidth::operator =( + VehicleWidth&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool VehicleWidth::operator ==( + const VehicleWidth& x) const +{ + return (m_value == x.m_value); +} + +bool VehicleWidth::operator !=( + const VehicleWidth& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void VehicleWidth::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t VehicleWidth::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& VehicleWidth::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "VehicleWidthCdrAux.ipp" + 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..f553fda52fc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidth.h @@ -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 VehicleWidth.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTH_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthCdrAux.hpp new file mode 100644 index 00000000000..008c7688e12 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VehicleWidthCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTHCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTHCDRAUX_HPP_ + +#include "VehicleWidth.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_VehicleWidth_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_VehicleWidth_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleWidth& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTHCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthCdrAux.ipp new file mode 100644 index 00000000000..f59cd944720 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VehicleWidthCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTHCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTHCDRAUX_IPP_ + +#include "VehicleWidthCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::VehicleWidth& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleWidth& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::VehicleWidth& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VehicleWidth& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTHCDRAUX_IPP_ + 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..ab9cf9833c8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthPubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "VehicleWidthPubSubTypes.h" +#include "VehicleWidthCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(VehicleWidth::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_VehicleWidth_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +VehicleWidthPubSubType::~VehicleWidthPubSubType() +{ +} + +bool VehicleWidthPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool VehicleWidthPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function VehicleWidthPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..a37d4f58c23 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VehicleWidthPubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "VehicleWidth.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~VehicleWidthPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VEHICLEWIDTH_PUBSUBTYPES_H_ + 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..d003d7b5940 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAcceleration.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 VerticalAcceleration.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +VerticalAcceleration::VerticalAcceleration() +{ +} + +VerticalAcceleration::~VerticalAcceleration() +{ +} + +VerticalAcceleration::VerticalAcceleration( + const VerticalAcceleration& x) +{ + m_vertical_acceleration_value = x.m_vertical_acceleration_value; + m_vertical_acceleration_confidence = x.m_vertical_acceleration_confidence; +} + +VerticalAcceleration::VerticalAcceleration( + VerticalAcceleration&& x) noexcept +{ + m_vertical_acceleration_value = std::move(x.m_vertical_acceleration_value); + m_vertical_acceleration_confidence = std::move(x.m_vertical_acceleration_confidence); +} + +VerticalAcceleration& 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; +} + +VerticalAcceleration& VerticalAcceleration::operator =( + VerticalAcceleration&& x) noexcept +{ + + 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 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 VerticalAcceleration::operator !=( + const VerticalAcceleration& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& VerticalAcceleration::vertical_acceleration_confidence() +{ + return m_vertical_acceleration_confidence; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "VerticalAccelerationCdrAux.ipp" + 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..df36fceb7b9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAcceleration.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATION_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATION_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "AccelerationConfidence.h" +#include "VerticalAccelerationValue.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationCdrAux.hpp new file mode 100644 index 00000000000..d751788d516 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VerticalAccelerationCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONCDRAUX_HPP_ + +#include "VerticalAcceleration.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_VerticalAcceleration_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_VerticalAcceleration_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VerticalAcceleration& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationCdrAux.ipp new file mode 100644 index 00000000000..ae26b6d946d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VerticalAccelerationCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONCDRAUX_IPP_ + +#include "VerticalAccelerationCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::VerticalAcceleration& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.vertical_acceleration_value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.vertical_acceleration_confidence(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VerticalAcceleration& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.vertical_acceleration_value() + << eprosima::fastcdr::MemberId(1) << data.vertical_acceleration_confidence() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::VerticalAcceleration& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.vertical_acceleration_value(); + break; + + case 1: + dcdr >> data.vertical_acceleration_confidence(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VerticalAcceleration& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONCDRAUX_IPP_ + 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..74aecbe10b8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationPubSubTypes.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 VerticalAccelerationPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "VerticalAccelerationPubSubTypes.h" +#include "VerticalAccelerationCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +VerticalAccelerationPubSubType::VerticalAccelerationPubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::VerticalAcceleration_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(VerticalAcceleration::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_VerticalAcceleration_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +VerticalAccelerationPubSubType::~VerticalAccelerationPubSubType() +{ +} + +bool VerticalAccelerationPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool VerticalAccelerationPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function VerticalAccelerationPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..57be2ce0115 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "VerticalAcceleration.h" + +#include "AccelerationConfidencePubSubTypes.h" +#include "VerticalAccelerationValuePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~VerticalAccelerationPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATION_PUBSUBTYPES_H_ + 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..9745c49024b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValue.cxx @@ -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 VerticalAccelerationValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace VerticalAccelerationValue_Constants { + + +} // namespace VerticalAccelerationValue_Constants + + +VerticalAccelerationValue::VerticalAccelerationValue() +{ +} + +VerticalAccelerationValue::~VerticalAccelerationValue() +{ +} + +VerticalAccelerationValue::VerticalAccelerationValue( + const VerticalAccelerationValue& x) +{ + m_value = x.m_value; +} + +VerticalAccelerationValue::VerticalAccelerationValue( + VerticalAccelerationValue&& x) noexcept +{ + m_value = x.m_value; +} + +VerticalAccelerationValue& VerticalAccelerationValue::operator =( + const VerticalAccelerationValue& x) +{ + + m_value = x.m_value; + return *this; +} + +VerticalAccelerationValue& VerticalAccelerationValue::operator =( + VerticalAccelerationValue&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool VerticalAccelerationValue::operator ==( + const VerticalAccelerationValue& x) const +{ + return (m_value == x.m_value); +} + +bool VerticalAccelerationValue::operator !=( + const VerticalAccelerationValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void VerticalAccelerationValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t VerticalAccelerationValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& VerticalAccelerationValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "VerticalAccelerationValueCdrAux.ipp" + 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..82cbee7d407 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValue.h @@ -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 VerticalAccelerationValue.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValueCdrAux.hpp new file mode 100644 index 00000000000..a88179855a0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValueCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VerticalAccelerationValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUECDRAUX_HPP_ + +#include "VerticalAccelerationValue.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_VerticalAccelerationValue_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_VerticalAccelerationValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VerticalAccelerationValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValueCdrAux.ipp new file mode 100644 index 00000000000..f2d5eb7f226 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValueCdrAux.ipp @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file VerticalAccelerationValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUECDRAUX_IPP_ + +#include "VerticalAccelerationValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::VerticalAccelerationValue& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VerticalAccelerationValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::VerticalAccelerationValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::VerticalAccelerationValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUECDRAUX_IPP_ + 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..5bacca7a0e5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValuePubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "VerticalAccelerationValuePubSubTypes.h" +#include "VerticalAccelerationValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(VerticalAccelerationValue::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_VerticalAccelerationValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +VerticalAccelerationValuePubSubType::~VerticalAccelerationValuePubSubType() +{ +} + +bool VerticalAccelerationValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool VerticalAccelerationValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function VerticalAccelerationValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..37ea0ce760e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/VerticalAccelerationValuePubSubTypes.h @@ -0,0 +1,147 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "VerticalAccelerationValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + +} // 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 ~VerticalAccelerationValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_VERTICALACCELERATIONVALUE_PUBSUBTYPES_H_ + 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..f5aa4890a18 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRate.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 YawRate.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + + + +YawRate::YawRate() +{ +} + +YawRate::~YawRate() +{ +} + +YawRate::YawRate( + const YawRate& x) +{ + m_yaw_rate_value = x.m_yaw_rate_value; + m_yaw_rate_confidence = x.m_yaw_rate_confidence; +} + +YawRate::YawRate( + YawRate&& x) noexcept +{ + m_yaw_rate_value = std::move(x.m_yaw_rate_value); + m_yaw_rate_confidence = std::move(x.m_yaw_rate_confidence); +} + +YawRate& 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; +} + +YawRate& YawRate::operator =( + YawRate&& x) noexcept +{ + + 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 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 YawRate::operator !=( + const YawRate& x) const +{ + return !(*this == x); +} + +/*! + * @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 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 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& 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& 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 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 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& 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& YawRate::yaw_rate_confidence() +{ + return m_yaw_rate_confidence; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "YawRateCdrAux.ipp" + 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..de9a8dd16eb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRate.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATE_H_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "YawRateConfidence.h" +#include "YawRateValue.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateCdrAux.hpp new file mode 100644 index 00000000000..efe614ad20f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file YawRateCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECDRAUX_HPP_ + +#include "YawRate.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_YawRate_max_cdr_typesize {17UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_YawRate_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::YawRate& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateCdrAux.ipp new file mode 100644 index 00000000000..a6e474c91cd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file YawRateCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECDRAUX_IPP_ + +#include "YawRateCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::YawRate& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.yaw_rate_value(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.yaw_rate_confidence(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::YawRate& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.yaw_rate_value() + << eprosima::fastcdr::MemberId(1) << data.yaw_rate_confidence() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::YawRate& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.yaw_rate_value(); + break; + + case 1: + dcdr >> data.yaw_rate_confidence(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::YawRate& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECDRAUX_IPP_ + 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..9b295341d88 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidence.cxx @@ -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 YawRateConfidence.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace YawRateConfidence_Constants { + + +} // namespace YawRateConfidence_Constants + + +YawRateConfidence::YawRateConfidence() +{ +} + +YawRateConfidence::~YawRateConfidence() +{ +} + +YawRateConfidence::YawRateConfidence( + const YawRateConfidence& x) +{ + m_value = x.m_value; +} + +YawRateConfidence::YawRateConfidence( + YawRateConfidence&& x) noexcept +{ + m_value = x.m_value; +} + +YawRateConfidence& YawRateConfidence::operator =( + const YawRateConfidence& x) +{ + + m_value = x.m_value; + return *this; +} + +YawRateConfidence& YawRateConfidence::operator =( + YawRateConfidence&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool YawRateConfidence::operator ==( + const YawRateConfidence& x) const +{ + return (m_value == x.m_value); +} + +bool YawRateConfidence::operator !=( + const YawRateConfidence& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void YawRateConfidence::value( + uint8_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +uint8_t YawRateConfidence::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +uint8_t& YawRateConfidence::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "YawRateConfidenceCdrAux.ipp" + 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..8aba07d1972 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidence.h @@ -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 YawRateConfidence.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidenceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidenceCdrAux.hpp new file mode 100644 index 00000000000..2468c875974 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidenceCdrAux.hpp @@ -0,0 +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 YawRateConfidenceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCECDRAUX_HPP_ + +#include "YawRateConfidence.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_YawRateConfidence_max_cdr_typesize {5UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_YawRateConfidence_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::YawRateConfidence& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidenceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidenceCdrAux.ipp new file mode 100644 index 00000000000..de4730f7e16 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidenceCdrAux.ipp @@ -0,0 +1,149 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file YawRateConfidenceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCECDRAUX_IPP_ + +#include "YawRateConfidenceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::YawRateConfidence& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::YawRateConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::YawRateConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::YawRateConfidence& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCECDRAUX_IPP_ + 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..77ed48b5974 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidencePubSubTypes.cxx @@ -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 YawRateConfidencePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "YawRateConfidencePubSubTypes.h" +#include "YawRateConfidenceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(YawRateConfidence::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_YawRateConfidence_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +YawRateConfidencePubSubType::~YawRateConfidencePubSubType() +{ +} + +bool YawRateConfidencePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool YawRateConfidencePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function YawRateConfidencePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..082f55b2e46 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateConfidencePubSubTypes.h @@ -0,0 +1,155 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "YawRateConfidence.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + +} // 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 ~YawRateConfidencePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATECONFIDENCE_PUBSUBTYPES_H_ + 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..33e82627d88 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRatePubSubTypes.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 YawRatePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "YawRatePubSubTypes.h" +#include "YawRateCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace etsi_its_cam_msgs { +namespace msg { + + +YawRatePubSubType::YawRatePubSubType() +{ + setName("etsi_its_cam_msgs::msg::dds_::YawRate_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(YawRate::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_YawRate_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +YawRatePubSubType::~YawRatePubSubType() +{ +} + +bool YawRatePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool YawRatePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function YawRatePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..054388f6dde --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRatePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "YawRate.h" + +#include "YawRateConfidencePubSubTypes.h" +#include "YawRateValuePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~YawRatePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATE_PUBSUBTYPES_H_ + 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..45dbf8c2cd0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValue.cxx @@ -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 YawRateValue.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace etsi_its_cam_msgs { + +namespace msg { + +namespace YawRateValue_Constants { + + +} // namespace YawRateValue_Constants + + +YawRateValue::YawRateValue() +{ +} + +YawRateValue::~YawRateValue() +{ +} + +YawRateValue::YawRateValue( + const YawRateValue& x) +{ + m_value = x.m_value; +} + +YawRateValue::YawRateValue( + YawRateValue&& x) noexcept +{ + m_value = x.m_value; +} + +YawRateValue& YawRateValue::operator =( + const YawRateValue& x) +{ + + m_value = x.m_value; + return *this; +} + +YawRateValue& YawRateValue::operator =( + YawRateValue&& x) noexcept +{ + + m_value = x.m_value; + return *this; +} + +bool YawRateValue::operator ==( + const YawRateValue& x) const +{ + return (m_value == x.m_value); +} + +bool YawRateValue::operator !=( + const YawRateValue& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member value + * @param _value New value for member value + */ +void YawRateValue::value( + int16_t _value) +{ + m_value = _value; +} + +/*! + * @brief This function returns the value of member value + * @return Value of member value + */ +int16_t YawRateValue::value() const +{ + return m_value; +} + +/*! + * @brief This function returns a reference to member value + * @return Reference to member value + */ +int16_t& YawRateValue::value() +{ + return m_value; +} + + + + +} // namespace msg + + +} // namespace etsi_its_cam_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "YawRateValueCdrAux.ipp" + 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..25c82b7b7fd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValue.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 + +#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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + int16_t m_value{0}; + +}; + +} // namespace msg + +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValueCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValueCdrAux.hpp new file mode 100644 index 00000000000..61477dfda86 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValueCdrAux.hpp @@ -0,0 +1,63 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file YawRateValueCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUECDRAUX_HPP_ + +#include "YawRateValue.h" + +constexpr uint32_t etsi_its_cam_msgs_msg_YawRateValue_max_cdr_typesize {6UL}; +constexpr uint32_t etsi_its_cam_msgs_msg_YawRateValue_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::YawRateValue& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValueCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValueCdrAux.ipp new file mode 100644 index 00000000000..57bdfb4c0bf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValueCdrAux.ipp @@ -0,0 +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 YawRateValueCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUECDRAUX_IPP_ + +#include "YawRateValueCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const etsi_its_cam_msgs::msg::YawRateValue& data, + size_t& current_alignment) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.value(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::YawRateValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.value() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + etsi_its_cam_msgs::msg::YawRateValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.value(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const etsi_its_cam_msgs::msg::YawRateValue& data) +{ + using namespace etsi_its_cam_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUECDRAUX_IPP_ + 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..c30e3a24526 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValuePubSubTypes.cxx @@ -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 YawRateValuePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "YawRateValuePubSubTypes.h" +#include "YawRateValueCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_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_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(YawRateValue::getMaxCdrSerializedSize()); +#else + etsi_its_cam_msgs_msg_YawRateValue_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +YawRateValuePubSubType::~YawRateValuePubSubType() +{ +} + +bool YawRateValuePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool YawRateValuePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function YawRateValuePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..63c3bea4047 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/etsi_its_cam_msgs/msg/YawRateValuePubSubTypes.h @@ -0,0 +1,149 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#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 +#include +#include +#include + +#include "YawRateValue.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + +} // 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 ~YawRateValuePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace etsi_its_cam_msgs + +#endif // _FAST_DDS_GENERATED_ETSI_ITS_CAM_MSGS_MSG_YAWRATEVALUE_PUBSUBTYPES_H_ + 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..6aa131b1ab5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/fastcdr/Cdr.h @@ -0,0 +1,3554 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT 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 +#include +#include +#include +#include +#include + +#include "fastcdr/fastcdr_dll.h" + +#include "fastcdr/CdrEncoding.hpp" +#include "fastcdr/cdr/fixed_size_string.hpp" +#include "fastcdr/detail/container_recursive_inspector.hpp" +#include "fastcdr/exceptions/BadParamException.h" +#include "fastcdr/exceptions/Exception.h" +#include "fastcdr/exceptions/NotEnoughMemoryException.h" +#include "fastcdr/FastBuffer.h" +#include "fastcdr/xcdr/external.hpp" +#include "fastcdr/xcdr/MemberId.hpp" +#include "fastcdr/xcdr/optional.hpp" + +#if !__APPLE__ && !__FreeBSD__ && !__VXWORKS__ +#include +#else +#include +#endif // if !__APPLE__ && !__FreeBSD__ && !__VXWORKS__ + +namespace eprosima { +namespace fastcdr { + +class Cdr; + +template +extern void serialize( + Cdr&, + const _T&); + +template +extern void deserialize( + Cdr&, + _T&); + +/*! + * @brief This class offers an interface to serialize/deserialize some basic types using CDR protocol inside an eprosima::fastcdr::FastBuffer. + * @ingroup FASTCDRAPIREFERENCE + */ +class Cdr +{ +public: + + /*! + * @brief This enumeration represents endianness types. + */ + typedef enum : uint8_t + { + //! @brief Big endianness. + BIG_ENDIANNESS = 0x0, + //! @brief Little endianness. + LITTLE_ENDIANNESS = 0x1 + } Endianness; + + //! Default endianess in the system. + Cdr_DllAPI static const Endianness DEFAULT_ENDIAN; + + /*! + * Used to decide, in encoding algorithms where member headers support a short header version and a long header + * version, which one will be used. + */ + typedef enum + { + //! Initially a short member header is allocated and cannot be changed. This option may cause an exception. + SHORT_HEADER, + //! Initially a long member header is allocated and cannot be changed. + LONG_HEADER, + //! Initially a short member header is allocated but can be changed to the longer version. + AUTO_WITH_SHORT_HEADER_BY_DEFAULT, + //! Initially a long member header is allocated but can be changed to the shorter version. + AUTO_WITH_LONG_HEADER_BY_DEFAULT + } XCdrHeaderSelection; + + /*! + * @brief This class stores the current state of a CDR serialization. + */ + class state + { + friend class Cdr; + + public: + + //! Default constructor. + Cdr_DllAPI state( + const Cdr& cdr); + + //! Copy constructor. + Cdr_DllAPI state( + const state& state); + + + //! Compares two states. + Cdr_DllAPI bool operator ==( + const state& other_state) const; + + private: + + state& operator =( + const state& state) = delete; + + //! The position in the buffer when the state was created. + const FastBuffer::iterator offset_; + + //! The position from the alignment is calculated, when the state was created. + const FastBuffer::iterator origin_; + + //! This attribute specifies if it is needed to swap the bytes when the state is created. + bool swap_bytes_ {false}; + + //! Stores the last datasize serialized/deserialized when the state was created. + size_t last_data_size_ {0}; + + //! Not related with the state. Next member id which will be encoded. + MemberId next_member_id_; + + //! Not related with the state. Used by encoding algorithms to set the encoded member size. + uint32_t member_size_ {0}; + + //! Not related with the state. Used by encoding algorithms to store the selected member header version. + XCdrHeaderSelection header_selection_ {XCdrHeaderSelection::AUTO_WITH_SHORT_HEADER_BY_DEFAULT}; + + //! Not related with the state. Used by encoding algorithms to store the allocated member header version. + XCdrHeaderSelection header_serialized_ {XCdrHeaderSelection::SHORT_HEADER}; + + //! Not related with the state. Used by encoding algorithms to store the previous encoding algorithm. + EncodingAlgorithmFlag previous_encoding_ {EncodingAlgorithmFlag::PLAIN_CDR2}; + }; + + /*! + * @brief This constructor creates an eprosima::fastcdr::Cdr object that can serialize/deserialize + * the assigned buffer. + * @param cdr_buffer 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 cdr_version Represents the type of encoding algorithm that will be used for the encoding. + * The default value is CdrVersion::XCDRv2. + */ + Cdr_DllAPI Cdr( + FastBuffer& cdr_buffer, + const Endianness endianness = DEFAULT_ENDIAN, + const CdrVersion cdr_version = XCDRv2); + + /*! + * @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. + * CdrVersion and EncodingAlgorithmFlag internal values will be changed to the ones specified by the + * encapsulation. + * @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_DllAPI 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_DllAPI Cdr& serialize_encapsulation(); + + /*! + * @brief Retrieves the CdrVersion used by the instance. + * @return Configured CdrVersion. + */ + Cdr_DllAPI CdrVersion get_cdr_version() const; + + /*! + * @brief Returns the EncodingAlgorithmFlag set in the encapsulation when the CDR type is + * CdrVersion::DDS_CDR, CdrVersion::XCDRv1 or CdrVersion::XCDRv2. + * @return The specified flag in the encapsulation. + */ + Cdr_DllAPI EncodingAlgorithmFlag get_encoding_flag() const; + + /*! + * @brief Sets the EncodingAlgorithmFlag for the encapsulation when the CDR type is + * CdrVersion::DDS_CDR, CdrVersion::XCDRv1 or CdrVersion::XCDRv2. + * This function only works when is called before starting the encoding/decoding. + * @param[in] encoding_flag Value to be used in the encapsulation. + * @return Indicates whether the setting was successful. + */ + Cdr_DllAPI bool set_encoding_flag( + EncodingAlgorithmFlag encoding_flag); + + /*! + * @brief This function returns the option flags when the CDR type is eprosima::fastcdr::DDS_CDR. + * @return The option flags. + */ + Cdr_DllAPI std::array get_dds_cdr_options() 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. + */ + Cdr_DllAPI void set_dds_cdr_options( + const std::array& options); + + /*! + * @brief This function sets the current endianness used by the CDR type. + * @param endianness The new endianness value. + */ + Cdr_DllAPI void change_endianness( + Endianness endianness); + + /*! + * @brief This function returns the current endianness used by the CDR type. + * @return The endianness. + */ + Cdr_DllAPI Endianness endianness() const; + + /*! + * @brief This function skips a number of bytes in the CDR stream buffer. + * @param num_bytes The number of bytes that will be jumped. + * @return True is returned when it works successfully. Otherwise, false is returned. + */ + Cdr_DllAPI bool jump( + size_t num_bytes); + + /*! + * @brief This function resets the current position in the buffer to the beginning. + */ + Cdr_DllAPI void reset(); + + /*! + * @brief This function returns the pointer to the current used buffer. + * @return Pointer to the starting position of the buffer. + */ + Cdr_DllAPI char* get_buffer_pointer(); + + /*! + * @brief This function returns the current position in the CDR stream. + * @return Pointer to the current position in the buffer. + */ + Cdr_DllAPI char* get_current_position(); + + /*! + * @brief This function returns the length of the serialized data inside the stream. + * @return The length of the serialized data. + */ + Cdr_DllAPI size_t get_serialized_data_length() const; + + /*! + * @brief Returns the number of bytes needed to align a position to certain data size. + * @param current_alignment Position to be aligned. + * @param data_size 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 data_size) + { + return (data_size - (current_alignment % data_size)) & (data_size - 1); + } + + /*! + * @brief Returns the current state of the CDR serialization process. + * @return The current state of the CDR serialization process. + */ + Cdr_DllAPI state get_state() const; + + /*! + * @brief Sets a previous state of the CDR serialization process; + * @param state Previous state that will be set. + */ + Cdr_DllAPI void set_state( + const state& state); + + /*! + * @brief This function moves the alignment forward. + * @param num_bytes The number of bytes the alignment should advance. + * @return True If alignment was moved successfully. + */ + Cdr_DllAPI bool move_alignment_forward( + size_t num_bytes); + + /*! + * @brief This function resets the alignment to the current position in the buffer. + */ + inline void reset_alignment() + { + origin_ = offset_; + last_data_size_ = 0; + } + + /*! + * @brief Encodes the value into the buffer. + * + * If previously a MemberId was set using operator<<, this operator will encode the value as a member of a type + * consistent with the set member identifier and according to the encoding algorithm used. + * + * In other case, the operator will simply encode the value. + * + * @param[in] value A reference to the value which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template + inline Cdr& operator <<( + const _T& value) + { + if (MEMBER_ID_INVALID == next_member_id_) + { + serialize(value); + } + else + { + serialize_member(next_member_id_, value); + + } + + return *this; + } + + /*! + * @brief Decodes the value from the buffer. + * + * If this operator is called while decoding members of a type, this operator will decode the value as a member + * according to the encoding algorithm used. + * + * In other case, the operator will simply decode the value. + * + * @param[out] value Reference to the variable where the value will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a position + * that exceeds the internal memory size. + */ + template + inline Cdr& operator >>( + _T& value) + { + if (MEMBER_ID_INVALID == next_member_id_) + { + deserialize(value); + } + else + { + deserialize_member(value); + } + return *this; + } + + /*! + * @brief Encodes the value of a type into the buffer. + * + * To do that, the encoder expects a function `serialize` to be provided by the type. + * + * @param[in] value A reference to the value which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, typename = void> + Cdr& serialize( + const _T& value) + { + eprosima::fastcdr::serialize(*this, value); + return *this; + } + + /*! + * @brief Encodes the value of a type with a different endianness. + * @param[in] value A reference to the value which will be encoded 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 encode into a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& serialize( + const _T& value, + Endianness endianness) + { + bool aux_swap = swap_bytes_; + swap_bytes_ = (swap_bytes_ && (static_cast(endianness_) == endianness)) || + (!swap_bytes_ && (static_cast(endianness_) != endianness)); + + try + { + serialize(value); + swap_bytes_ = aux_swap; + } + catch (exception::Exception& ex) + { + swap_bytes_ = aux_swap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief Encodes the value of a enumerator into the buffer. + * + * @param[in] value A reference to the value which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + int32_t>::value>::type* = nullptr> + Cdr& serialize( + const _T& value) + { + return serialize(static_cast(value)); + } + + /*! + * @brief Encodes the value of a enumerator into the buffer. + * + * @param[in] value A reference to the value which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + uint32_t>::value>::type* = nullptr> + Cdr& serialize( + const _T& value) + { + return serialize(static_cast(value)); + } + + /*! + * @brief Encodes the value of a enumerator into the buffer. + * + * @param[in] value A reference to the value which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + int16_t>::value>::type* = nullptr> + Cdr& serialize( + const _T& value) + { + return serialize(static_cast(value)); + } + + /*! + * @brief Encodes the value of a enumerator into the buffer. + * + * @param[in] value A reference to the value which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + uint16_t>::value>::type* = nullptr> + Cdr& serialize( + const _T& value) + { + return serialize(static_cast(value)); + } + + /*! + * @brief Encodes the value of a enumerator into the buffer. + * + * @param[in] value A reference to the value which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + int8_t>::value>::type* = nullptr> + Cdr& serialize( + const _T& value) + { + return serialize(static_cast(value)); + } + + /*! + * @brief Encodes the value of a enumerator into the buffer. + * + * @param[in] value A reference to the value which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + uint8_t>::value>::type* = nullptr> + Cdr& serialize( + const _T& value) + { + return serialize(static_cast(value)); + } + + /*! + * @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. + */ + Cdr_DllAPI Cdr& serialize( + const uint8_t& octet_t); + + /*! + * @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_DllAPI Cdr& serialize( + const char 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. + */ + Cdr_DllAPI Cdr& serialize( + const int8_t int8); + + /*! + * @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. + */ + Cdr_DllAPI Cdr& serialize( + const uint16_t ushort_t); + + /*! + * @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_DllAPI Cdr& serialize( + const int16_t short_t); + + /*! + * @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. + */ + Cdr_DllAPI Cdr& serialize( + const uint32_t ulong_t); + + /*! + * @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_DllAPI Cdr& serialize( + const int32_t long_t); + + /*! + * @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. + */ + Cdr_DllAPI Cdr& serialize( + const wchar_t wchar); + + /*! + * @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. + */ + Cdr_DllAPI Cdr& serialize( + const uint64_t ulonglong_t); + + /*! + * @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_DllAPI Cdr& serialize( + const int64_t longlong_t); + + /*! + * @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_DllAPI Cdr& serialize( + const float float_t); + + /*! + * @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_DllAPI Cdr& serialize( + const double double_t); + + /*! + * @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_DllAPI Cdr& serialize( + const long double ldouble_t); + + /*! + * @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_DllAPI Cdr& serialize( + const bool 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. + */ + Cdr_DllAPI Cdr& serialize( + char* 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_DllAPI 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_DllAPI Cdr& serialize( + const wchar_t* string_t); + + /*! + * @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. + * @exception exception::BadParamException This exception is thrown when trying to serialize a string with null characters. + */ + TEMPLATE_SPEC + Cdr& serialize( + const std::string& string_t) + { + // Check there are no null characters in the string. + const char* c_str = string_t.c_str(); + const auto str_len = strlen(c_str); + if (string_t.size() > str_len) + { + throw exception::BadParamException("The string contains null characters"); + } + + return serialize_sequence(c_str, str_len + 1); + } + + /*! + * @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. + */ + TEMPLATE_SPEC + Cdr& serialize( + const std::wstring& string_t) + { + return serialize(string_t.c_str()); + } + + /*! + * @brief Encodes a eprosima::fastcdr::fixed_string in the buffer. + * @param[in] value A reference to the fixed string which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& serialize( + const fixed_string& value) + { + return serialize(value.c_str()); + } + + /*! + * @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 + Cdr& serialize( + const std::array<_T, _Size>& array_t) + { + if (!is_multi_array_primitive(&array_t)) + { + Cdr::state dheader_state {allocate_xcdrv2_dheader()}; + + serialize_array(array_t.data(), array_t.size()); + + set_xcdrv2_dheader(dheader_state); + } + else + { + serialize_array(array_t.data(), array_t.size()); + } + + return *this; + } + + /*! + * @brief This function template serializes a sequence of non-primitive. + * @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::value && + !std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& serialize( + const std::vector<_T, _Alloc>& vector_t) + { + Cdr::state dheader_state {allocate_xcdrv2_dheader()}; + + serialize(static_cast(vector_t.size())); + + try + { + serialize_array(vector_t.data(), vector_t.size()); + } + catch (exception::Exception& ex) + { + set_state(dheader_state); + ex.raise(); + } + + set_xcdrv2_dheader(dheader_state); + + return *this; + } + + /*! + * @brief This function template serializes a sequence of primitive. + * @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::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& serialize( + const std::vector<_T, _Alloc>& vector_t) + { + state state_before_error(*this); + + serialize(static_cast(vector_t.size())); + + try + { + serialize_array(vector_t.data(), vector_t.size()); + } + catch (exception::Exception& ex) + { + set_state(state_before_error); + ex.raise(); + } + + if (CdrVersion::XCDRv2 == cdr_version_) + { + serialized_member_size_ = get_serialized_member_size<_T>(); + } + + return *this; + } + + /*! + * @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_SPEC + Cdr& serialize( + const std::vector& vector_t) + { + return serialize_bool_sequence(vector_t); + } + + /*! + * @brief This function template serializes a map of non-primitive. + * @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::value && + !std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& serialize( + const std::map<_K, _T>& map_t) + { + Cdr::state dheader_state {allocate_xcdrv2_dheader()}; + + serialize(static_cast(map_t.size())); + + try + { + for (auto it_pair = map_t.begin(); it_pair != map_t.end(); ++it_pair) + { + serialize(it_pair->first); + serialize(it_pair->second); + } + } + catch (exception::Exception& ex) + { + set_state(dheader_state); + ex.raise(); + } + + set_xcdrv2_dheader(dheader_state); + + return *this; + } + + /*! + * @brief This function template serializes a map of primitive. + * @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::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& serialize( + const std::map<_K, _T>& map_t) + { + state state_(*this); + + serialize(static_cast(map_t.size())); + + try + { + for (auto it_pair = map_t.begin(); it_pair != map_t.end(); ++it_pair) + { + serialize(it_pair->first); + serialize(it_pair->second); + } + } + catch (exception::Exception& ex) + { + set_state(state_); + ex.raise(); + } + + return *this; + } + + /*! + * @brief Encodes the value of a bitset into the buffer. + * + * @param[in] value A reference to the value which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template ::type* = nullptr> + Cdr& serialize( + const std::bitset& value) + { + return serialize(static_cast(value.to_ulong())); + } + + template ::type* = nullptr> + Cdr& serialize( + const std::bitset& value) + { + return serialize(static_cast(value.to_ulong())); + } + + template ::type* = nullptr> + Cdr& serialize( + const std::bitset& value) + { + return serialize(static_cast(value.to_ulong())); + } + + template ::type* = nullptr> + Cdr& serialize( + const std::bitset& value) + { + return serialize(static_cast(value.to_ullong())); + } + + /*! + * @brief Encodes an array of a type not managed by this encoder into the buffer. + * + * To do that, the encoder expects a function `serialize` to be provided by the type. + * + * @param[in] value Array which will be encoded in the buffer. + * @param[in] num_elements 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 encode into a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& serialize_array( + const _T* value, + size_t num_elements) + { + for (size_t count = 0; count < num_elements; ++count) + { + serialize(value[count]); + } + 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 num_elements 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& serialize_array( + const _T* type_t, + size_t num_elements, + Endianness endianness) + { + bool aux_swap = swap_bytes_; + swap_bytes_ = (swap_bytes_ && (static_cast(endianness_) == endianness)) || + (!swap_bytes_ && (static_cast(endianness_) != endianness)); + + try + { + serialize_array(type_t, num_elements); + swap_bytes_ = aux_swap; + } + catch (exception::Exception& ex) + { + swap_bytes_ = aux_swap; + ex.raise(); + } + + 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 num_elements 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_SPEC + Cdr& serialize_array( + const uint8_t* octet_t, + size_t num_elements) + { + return serialize_array(reinterpret_cast(octet_t), num_elements); + } + + /*! + * @brief This function serializes an array of characters. + * @param char_t The array of characters that will be serialized in the buffer. + * @param num_elements 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_DllAPI Cdr& serialize_array( + const char* char_t, + size_t num_elements); + + /*! + * @brief This function serializes an array of int8_t. + * @param int8 The sequence of int8_t that will be serialized in the buffer. + * @param num_elements 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_SPEC + Cdr& serialize_array( + const int8_t* int8, + size_t num_elements) + { + return serialize_array(reinterpret_cast(int8), num_elements); + } + + /*! + * @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 num_elements 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_SPEC + Cdr& serialize_array( + const uint16_t* ushort_t, + size_t num_elements) + { + return serialize_array(reinterpret_cast(ushort_t), num_elements); + } + + /*! + * @brief This function serializes an array of shorts. + * @param short_t The array of shorts that will be serialized in the buffer. + * @param num_elements 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_DllAPI Cdr& serialize_array( + const int16_t* short_t, + size_t num_elements); + + /*! + * @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 num_elements 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_SPEC + Cdr& serialize_array( + const uint32_t* ulong_t, + size_t num_elements) + { + return serialize_array(reinterpret_cast(ulong_t), num_elements); + } + + /*! + * @brief This function serializes an array of longs. + * @param long_t The array of longs that will be serialized in the buffer. + * @param num_elements 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_DllAPI Cdr& serialize_array( + const int32_t* long_t, + size_t num_elements); + + /*! + * @brief This function serializes an array of wide-chars. + * @param wchar The array of wide-chars that will be serialized in the buffer. + * @param num_elements 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_DllAPI Cdr& serialize_array( + const wchar_t* wchar, + size_t num_elements); + + /*! + * @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 num_elements 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_SPEC + Cdr& serialize_array( + const uint64_t* ulonglong_t, + size_t num_elements) + { + return serialize_array(reinterpret_cast(ulonglong_t), num_elements); + } + + /*! + * @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 num_elements 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_DllAPI Cdr& serialize_array( + const int64_t* longlong_t, + size_t num_elements); + + /*! + * @brief This function serializes an array of floats. + * @param float_t The array of floats that will be serialized in the buffer. + * @param num_elements 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_DllAPI Cdr& serialize_array( + const float* float_t, + size_t num_elements); + + /*! + * @brief This function serializes an array of doubles. + * @param double_t The array of doubles that will be serialized in the buffer. + * @param num_elements 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_DllAPI Cdr& serialize_array( + const double* double_t, + size_t num_elements); + + /*! + * @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 num_elements 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. + * @note Due to internal representation differences, WIN32 and *NIX like systems are not compatible. + */ + Cdr_DllAPI Cdr& serialize_array( + const long double* ldouble_t, + size_t num_elements); + + /*! + * @brief This function serializes an array of booleans. + * @param bool_t The array of booleans that will be serialized in the buffer. + * @param num_elements 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_DllAPI Cdr& serialize_array( + const bool* bool_t, + size_t num_elements); + + /*! + * @brief This function serializes an array of strings. + * @param string_t The array of strings that will be serialized in the buffer. + * @param num_elements 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_SPEC + Cdr& serialize_array( + const std::string* string_t, + size_t num_elements) + { + for (size_t count = 0; count < num_elements; ++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 num_elements 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_SPEC + Cdr& serialize_array( + const std::wstring* string_t, + size_t num_elements) + { + for (size_t count = 0; count < num_elements; ++count) + { + serialize(string_t[count].c_str()); + } + return *this; + } + + /*! + * @brief Encodes an array of fixed strings. + * @param[in] value Array of fixed strings which will be encoded in the buffer. + * @param[in] num_elements 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 encode into a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& serialize_array( + const fixed_string* value, + size_t num_elements) + { + for (size_t count = 0; count < num_elements; ++count) + { + serialize(value[count].c_str()); + } + return *this; + } + + /*! + * @brief Encodes an std::vector of primitives as an array. + * @param[in] value Reference to a std::vector. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& serialize_array( + const std::vector<_T, _Alloc>& value) + { + serialize_array(value.data(), value.size()); + + return *this; + } + + /*! + * @brief Encodes an std::vector of non-primitives as an array. + * @param[in] value Reference to a std::vector. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template::value && + !std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& serialize_array( + const std::vector<_T, _Alloc>& value) + { + Cdr::state dheader_state {allocate_xcdrv2_dheader()}; + + serialize_array(value.data(), value.size()); + + set_xcdrv2_dheader(dheader_state); + + return *this; + } + + /*! + * @brief Encodes an std::vector as an array with a different endianness. + * @param[in] value Reference to a std::vector. + * @param[in] 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 encode into a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& serialize_array( + const std::vector<_T, _Alloc>& value, + Endianness endianness) + { + bool aux_swap = swap_bytes_; + swap_bytes_ = (swap_bytes_ && (static_cast(endianness_) == endianness)) || + (!swap_bytes_ && (static_cast(endianness_) != endianness)); + + try + { + serialize_array(value); + swap_bytes_ = aux_swap; + } + catch (exception::Exception& ex) + { + swap_bytes_ = aux_swap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief Encodes an std::vector of booleans as an array. + * @param[in] value Reference to a std::vector. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + TEMPLATE_SPEC + Cdr& serialize_array( + const std::vector& value) + { + serialize_bool_array(value); + + return *this; + } + + /*! + * @brief This function template serializes a raw sequence of non-primitives + * @param sequence_t Pointer to the sequence that will be serialized in the buffer. + * @param num_elements 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::value && + !std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& serialize_sequence( + const _T* sequence_t, + size_t num_elements) + { + Cdr::state dheader_state {allocate_xcdrv2_dheader()}; + + serialize(static_cast(num_elements)); + + try + { + serialize_array(sequence_t, num_elements); + } + catch (exception::Exception& ex) + { + set_state(dheader_state); + ex.raise(); + } + + set_xcdrv2_dheader(dheader_state); + + return *this; + } + + /*! + * @brief This function template serializes a raw sequence of primitives + * @param sequence_t Pointer to the sequence that will be serialized in the buffer. + * @param num_elements 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::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& serialize_sequence( + const _T* sequence_t, + size_t num_elements) + { + state state_before_error(*this); + + serialize(static_cast(num_elements)); + + try + { + serialize_array(sequence_t, num_elements); + } + catch (exception::Exception& ex) + { + set_state(state_before_error); + ex.raise(); + } + + if (CdrVersion::XCDRv2 == cdr_version_) + { + serialized_member_size_ = get_serialized_member_size<_T>(); + } + + 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 num_elements 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& serialize_sequence( + const _T* sequence_t, + size_t num_elements, + Endianness endianness) + { + bool aux_swap = swap_bytes_; + swap_bytes_ = (swap_bytes_ && (static_cast(endianness_) == endianness)) || + (!swap_bytes_ && (static_cast(endianness_) != endianness)); + + try + { + serialize_sequence(sequence_t, num_elements); + swap_bytes_ = aux_swap; + } + catch (exception::Exception& ex) + { + swap_bytes_ = aux_swap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief Decodes the value of a type from the buffer. + * + * To do that, the encoder expects a function `deserialize` to be provided by the type. + * + * @param[out] value Reference to the variable where the value will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, typename = void> + Cdr& deserialize( + _T& value) + { + eprosima::fastcdr::deserialize(*this, value); + return *this; + } + + /*! + * @brief Decodes the value of a type with a different endianness. + * @param[out] value Reference to the variable where the value will be stored after decoding from the buffer. + * @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 decode from a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& deserialize( + _T& value, + Endianness endianness) + { + bool aux_swap = swap_bytes_; + swap_bytes_ = (swap_bytes_ && (static_cast(endianness_) == endianness)) || + (!swap_bytes_ && (static_cast(endianness_) != endianness)); + + try + { + deserialize(value); + swap_bytes_ = aux_swap; + } + catch (exception::Exception& ex) + { + swap_bytes_ = aux_swap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief Decodes an enumeration from the buffer. + * @param[out] value Reference to the variable where the enumeration will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + int32_t>::value>::type* = nullptr> + Cdr& deserialize( + _T& value) + { + int32_t decode_value {0}; + deserialize(decode_value); + value = static_cast<_T>(decode_value); + return *this; + } + + /*! + * @brief Decodes an enumeration from the buffer. + * @param[out] value Reference to the variable where the enumeration will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + uint32_t>::value>::type* = nullptr> + Cdr& deserialize( + _T& value) + { + uint32_t decode_value {0}; + deserialize(decode_value); + value = static_cast<_T>(decode_value); + return *this; + } + + /*! + * @brief Decodes an enumeration from the buffer. + * @param[out] value Reference to the variable where the enumeration will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + int16_t>::value>::type* = nullptr> + Cdr& deserialize( + _T& value) + { + int16_t decode_value {0}; + deserialize(decode_value); + value = static_cast<_T>(decode_value); + return *this; + } + + /*! + * @brief Decodes an enumeration from the buffer. + * @param[out] value Reference to the variable where the enumeration will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + uint16_t>::value>::type* = nullptr> + Cdr& deserialize( + _T& value) + { + uint16_t decode_value {0}; + deserialize(decode_value); + value = static_cast<_T>(decode_value); + return *this; + } + + /*! + * @brief Decodes an enumeration from the buffer. + * @param[out] value Reference to the variable where the enumeration will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + int8_t>::value>::type* = nullptr> + Cdr& deserialize( + _T& value) + { + int8_t decode_value {0}; + deserialize(decode_value); + value = static_cast<_T>(decode_value); + return *this; + } + + /*! + * @brief Decodes an enumeration from the buffer. + * @param[out] value Reference to the variable where the enumeration will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + uint8_t>::value>::type* = nullptr> + Cdr& deserialize( + _T& value) + { + uint8_t decode_value {0}; + deserialize(decode_value); + value = static_cast<_T>(decode_value); + 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. + */ + TEMPLATE_SPEC + Cdr& deserialize( + uint8_t& octet_t) + { + return deserialize(reinterpret_cast(octet_t)); + } + + /*! + * @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_DllAPI Cdr& deserialize( + char& 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. + */ + TEMPLATE_SPEC + Cdr& deserialize( + int8_t& int8) + { + return deserialize(reinterpret_cast(int8)); + } + + /*! + * @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. + */ + TEMPLATE_SPEC + Cdr& deserialize( + uint16_t& ushort_t) + { + return deserialize(reinterpret_cast(ushort_t)); + } + + /*! + * @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_DllAPI Cdr& deserialize( + int16_t& short_t); + + /*! + * @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. + */ + TEMPLATE_SPEC + Cdr& deserialize( + uint32_t& ulong_t) + { + return deserialize(reinterpret_cast(ulong_t)); + } + + /*! + * @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_DllAPI Cdr& deserialize( + int32_t& long_t); + + /*! + * @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. + */ + TEMPLATE_SPEC + Cdr& deserialize( + wchar_t& wchar) + { + uint16_t ret; + deserialize(ret); + 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. + */ + TEMPLATE_SPEC + Cdr& deserialize( + uint64_t& ulonglong_t) + { + return deserialize(reinterpret_cast(ulonglong_t)); + } + + /*! + * @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_DllAPI Cdr& deserialize( + int64_t& longlong_t); + + /*! + * @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_DllAPI Cdr& deserialize( + float& float_t); + + /*! + * @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_DllAPI Cdr& deserialize( + double& double_t); + + /*! + * @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_DllAPI Cdr& deserialize( + long double& ldouble_t); + + /*! + * @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_DllAPI Cdr& deserialize( + bool& 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. + * @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_DllAPI 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. + * @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_DllAPI Cdr& deserialize( + wchar_t*& string_t); + + /*! + * @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. + */ + TEMPLATE_SPEC + Cdr& deserialize( + std::string& string_t) + { + uint32_t length = 0; + const char* str = read_string(length); + string_t.assign(str, length); + return *this; + } + + /*! + * @brief This function deserializes a std::wstring. + * @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. + */ + TEMPLATE_SPEC + Cdr& deserialize( + std::wstring& string_t) + { + uint32_t length = 0; + string_t = read_wstring(length); + return *this; + } + + /*! + * @brief Decodes a fixed string. + * @param[out] value Reference to the variable where the fixed string will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& deserialize( + fixed_string& value) + { + uint32_t length = 0; + const char* str = read_string(length); + value.assign(str, length); + 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 + Cdr& deserialize( + std::array<_T, _Size>& array_t) + { + if (CdrVersion::XCDRv2 == cdr_version_ && !is_multi_array_primitive(&array_t)) + { + uint32_t dheader {0}; + deserialize(dheader); + + uint32_t count {0}; + auto offset = offset_; + while (offset_ - offset < dheader && count < _Size) + { + deserialize_array(&array_t.data()[count], 1); + ++count; + } + + if (offset_ - offset != dheader) + { + throw exception::BadParamException("Member size greater than size specified by DHEADER"); + } + } + else + { + return deserialize_array(array_t.data(), array_t.size()); + } + + return *this; + } + + /*! + * @brief This function template deserializes a sequence of non-primitive. + * @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::value && + !std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& deserialize( + std::vector<_T, _Alloc>& vector_t) + { + uint32_t sequence_length {0}; + + if (CdrVersion::XCDRv2 == cdr_version_) + { + uint32_t dheader {0}; + deserialize(dheader); + + auto offset = offset_; + + deserialize(sequence_length); + + if (0 == sequence_length) + { + vector_t.clear(); + return *this; + } + else + { + vector_t.resize(sequence_length); + } + + uint32_t count {0}; + while (offset_ - offset < dheader && count < sequence_length) + { + deserialize(vector_t.data()[count]); + ++count; + } + + if (offset_ - offset != dheader) + { + throw exception::BadParamException("Member size differs from the size specified by DHEADER"); + } + } + else + { + state state_before_error(*this); + + deserialize(sequence_length); + + if (sequence_length == 0) + { + vector_t.clear(); + return *this; + } + + if ((end_ - offset_) < sequence_length) + { + set_state(state_before_error); + throw exception::NotEnoughMemoryException( + exception::NotEnoughMemoryException::NOT_ENOUGH_MEMORY_MESSAGE_DEFAULT); + } + + try + { + vector_t.resize(sequence_length); + return deserialize_array(vector_t.data(), vector_t.size()); + } + catch (exception::Exception& ex) + { + set_state(state_before_error); + ex.raise(); + } + } + + return *this; + } + + /*! + * @brief This function template deserializes a sequence of primitive. + * @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::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& deserialize( + std::vector<_T, _Alloc>& vector_t) + { + uint32_t sequence_length = 0; + state state_before_error(*this); + + deserialize(sequence_length); + + if (sequence_length == 0) + { + vector_t.clear(); + return *this; + } + + if ((end_ - offset_) < sequence_length) + { + set_state(state_before_error); + throw exception::NotEnoughMemoryException( + exception::NotEnoughMemoryException::NOT_ENOUGH_MEMORY_MESSAGE_DEFAULT); + } + + try + { + vector_t.resize(sequence_length); + return deserialize_array(vector_t.data(), vector_t.size()); + } + catch (exception::Exception& ex) + { + set_state(state_before_error); + ex.raise(); + } + + return *this; + } + + /*! + * @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_SPEC + Cdr& deserialize( + std::vector& vector_t) + { + return deserialize_bool_sequence(vector_t); + } + + /*! + * @brief This function template deserializes a map of non-primitive. + * @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::value && + !std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& deserialize( + std::map<_K, _T>& map_t) + { + if (CdrVersion::XCDRv2 == cdr_version_) + { + uint32_t dheader {0}; + deserialize(dheader); + + auto offset = offset_; + + uint32_t map_length {0}; + deserialize(map_length); + + map_t.clear(); + + uint32_t count {0}; + while (offset_ - offset < dheader && count < map_length) + { + _K key; + _T val; + deserialize(key); + deserialize(val); + map_t.emplace(std::pair<_K, _T>(std::move(key), std::move(val))); + ++count; + } + + if (offset_ - offset != dheader) + { + throw exception::BadParamException("Member size greater than size specified by DHEADER"); + } + } + else + { + uint32_t sequence_length = 0; + state state_(*this); + + deserialize(sequence_length); + + map_t.clear(); + + try + { + for (uint32_t i = 0; i < sequence_length; ++i) + { + _K key; + _T value; + deserialize(key); + deserialize(value); + map_t.emplace(std::pair<_K, _T>(std::move(key), std::move(value))); + } + } + catch (exception::Exception& ex) + { + set_state(state_); + ex.raise(); + } + } + + return *this; + } + + /*! + * @brief This function template deserializes a map of primitive. + * @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::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& deserialize( + std::map<_K, _T>& map_t) + { + uint32_t sequence_length = 0; + state state_(*this); + + deserialize(sequence_length); + + try + { + for (uint32_t i = 0; i < sequence_length; ++i) + { + _K key; + _T value; + deserialize(key); + deserialize(value); + map_t.emplace(std::pair<_K, _T>(std::move(key), std::move(value))); + } + } + catch (exception::Exception& ex) + { + set_state(state_); + ex.raise(); + } + + return *this; + } + + /*! + * @brief Decodes a bitset from the buffer. + * @param[out] value Reference to the variable where the bitset will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template ::type* = nullptr> + Cdr& deserialize( + std::bitset& value) + { + uint8_t decode_value {0}; + deserialize(decode_value); + value = decode_value; + return *this; + } + + template ::type* = nullptr> + Cdr& deserialize( + std::bitset& value) + { + uint16_t decode_value {0}; + deserialize(decode_value); + value = decode_value; + return *this; + } + + template ::type* = nullptr> + Cdr& deserialize( + std::bitset& value) + { + uint32_t decode_value {0}; + deserialize(decode_value); + value = decode_value; + return *this; + } + + template ::type* = nullptr> + Cdr& deserialize( + std::bitset& value) + { + uint64_t decode_value {0}; + deserialize(decode_value); + value = decode_value; + return *this; + } + + /*! + * @brief Decodes an array of a type not managed by this encoder from the buffer. + * + * To do that, the encoder expects a function `deserialize` to be provided by the type. + * + * @param[out] value Reference to the variable where the array will be stored after decoding from the buffer. + * @param[in] num_elements 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 decode from a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& deserialize_array( + _T* value, + size_t num_elements) + { + for (size_t count = 0; count < num_elements; ++count) + { + deserialize(value[count]); + } + 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 num_elements Number of the elements in the array. + * @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& deserialize_array( + _T* type_t, + size_t num_elements, + Endianness endianness) + { + bool aux_swap = swap_bytes_; + swap_bytes_ = (swap_bytes_ && (static_cast(endianness_) == endianness)) || + (!swap_bytes_ && (static_cast(endianness_) != endianness)); + + try + { + deserialize_array(type_t, num_elements); + swap_bytes_ = aux_swap; + } + catch (exception::Exception& ex) + { + swap_bytes_ = aux_swap; + ex.raise(); + } + + 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 num_elements 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_SPEC + Cdr& deserialize_array( + uint8_t* octet_t, + size_t num_elements) + { + return deserialize_array(reinterpret_cast(octet_t), num_elements); + } + + /*! + * @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 num_elements 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_DllAPI Cdr& deserialize_array( + char* char_t, + size_t num_elements); + + /*! + * @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 num_elements 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_SPEC + Cdr& deserialize_array( + int8_t* int8, + size_t num_elements) + { + return deserialize_array(reinterpret_cast(int8), num_elements); + } + + /*! + * @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 num_elements 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_SPEC + Cdr& deserialize_array( + uint16_t* ushort_t, + size_t num_elements) + { + return deserialize_array(reinterpret_cast(ushort_t), num_elements); + } + + /*! + * @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 num_elements 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_DllAPI Cdr& deserialize_array( + int16_t* short_t, + size_t num_elements); + + /*! + * @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 num_elements 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_SPEC + Cdr& deserialize_array( + uint32_t* ulong_t, + size_t num_elements) + { + return deserialize_array(reinterpret_cast(ulong_t), num_elements); + } + + /*! + * @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 num_elements 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_DllAPI Cdr& deserialize_array( + int32_t* long_t, + size_t num_elements); + + /*! + * @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 num_elements 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_DllAPI Cdr& deserialize_array( + wchar_t* wchar, + size_t num_elements); + + /*! + * @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 num_elements 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_SPEC + Cdr& deserialize_array( + uint64_t* ulonglong_t, + size_t num_elements) + { + return deserialize_array(reinterpret_cast(ulonglong_t), num_elements); + } + + /*! + * @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 num_elements 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_DllAPI Cdr& deserialize_array( + int64_t* longlong_t, + size_t num_elements); + + /*! + * @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 num_elements 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_DllAPI Cdr& deserialize_array( + float* float_t, + size_t num_elements); + + /*! + * @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 num_elements 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_DllAPI Cdr& deserialize_array( + double* double_t, + size_t num_elements); + + /*! + * @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 num_elements 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. + * @note Due to internal representation differences, WIN32 and *NIX like systems are not compatible. + */ + Cdr_DllAPI Cdr& deserialize_array( + long double* ldouble_t, + size_t num_elements); + + /*! + * @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 num_elements 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_DllAPI Cdr& deserialize_array( + bool* bool_t, + size_t num_elements); + + /*! + * @brief Decodes an array of primitives on a std::vector. + * + * std::vector must have allocated the number of element of the array. + * + * @param[out] value Reference to the std::vector where the array will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& deserialize_array( + std::vector<_T, _Alloc>& value) + { + deserialize_array(value.data(), value.size()); + + return *this; + } + + /*! + * @brief Decodes an array of non-primitives on a std::vector. + * + * std::vector must have allocated the number of element of the array. + * + * @param[out] value Reference to the std::vector where the array will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template::value && + !std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& deserialize_array( + std::vector<_T, _Alloc>& value) + { + if (CdrVersion::XCDRv2 == cdr_version_) + { + uint32_t dheader {0}; + deserialize(dheader); + + uint32_t count {0}; + auto offset = offset_; + while (offset_ - offset < dheader && count < value.size()) + { + deserialize_array(&value.data()[count], 1); + ++count; + } + + if (offset_ - offset != dheader) + { + throw exception::BadParamException("Member size greater than size specified by DHEADER"); + } + } + else + { + return deserialize_array(value.data(), value.size()); + } + + return *this; + } + + /*! + * @brief Decodes an array of non-primitives on a std::vector with a different endianness. + * + * std::vector must have allocated the number of element of the array. + * + * @param[out] value Reference to the std::vector where the array will be stored after decoding from the buffer. + * @param[in] 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 decode from a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& deserialize_array( + std::vector<_T, _Alloc>& value, + Endianness endianness) + { + bool aux_swap = swap_bytes_; + swap_bytes_ = (swap_bytes_ && (static_cast(endianness_) == endianness)) || + (!swap_bytes_ && (static_cast(endianness_) != endianness)); + + try + { + deserialize_array(value); + swap_bytes_ = aux_swap; + } + catch (exception::Exception& ex) + { + swap_bytes_ = aux_swap; + ex.raise(); + } + + return *this; + } + + /*! + * @brief Decodes an array of booleans on a std::vector. + * + * std::vector must have allocated the number of element of the array. + * + * @param[out] value Reference to the std::vector where the array will be stored after decoding from the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + TEMPLATE_SPEC + Cdr& deserialize_array( + std::vector& value) + { + deserialize_bool_array(value); + + return *this; + } + + /*! + * @brief This function template deserializes a raw sequence of non-primitives. + * 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 num_elements 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::value && + !std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& deserialize_sequence( + _T*& sequence_t, + size_t& num_elements) + { + uint32_t sequence_length {0}; + + if (CdrVersion::XCDRv2 == cdr_version_) + { + uint32_t dheader {0}; + deserialize(dheader); + + auto offset = offset_; + + deserialize(sequence_length); + + try + { + sequence_t = reinterpret_cast<_T*>(calloc(sequence_length, sizeof(_T))); + + uint32_t count {0}; + while (offset_ - offset < dheader && count < sequence_length) + { + deserialize(sequence_t[count]); + ++count; + } + + if (offset_ - offset != dheader) + { + throw exception::BadParamException("Member size greater than size specified by DHEADER"); + } + } + catch (exception::Exception& ex) + { + free(sequence_t); + sequence_t = NULL; + ex.raise(); + } + } + else + { + state state_before_error(*this); + + deserialize(sequence_length); + + if ((end_ - offset_) < sequence_length) + { + set_state(state_before_error); + throw exception::NotEnoughMemoryException( + exception::NotEnoughMemoryException::NOT_ENOUGH_MEMORY_MESSAGE_DEFAULT); + } + + try + { + sequence_t = reinterpret_cast<_T*>(calloc(sequence_length, sizeof(_T))); + deserialize_array(sequence_t, sequence_length); + } + catch (exception::Exception& ex) + { + free(sequence_t); + sequence_t = NULL; + set_state(state_before_error); + ex.raise(); + } + } + + num_elements = sequence_length; + return *this; + } + + /*! + * @brief This function template deserializes a raw sequence of primitives. + * 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 num_elements 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::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + Cdr& deserialize_sequence( + _T*& sequence_t, + size_t& num_elements) + { + uint32_t sequence_length = 0; + state state_before_error(*this); + + deserialize(sequence_length); + + try + { + sequence_t = reinterpret_cast<_T*>(calloc(sequence_length, sizeof(_T))); + deserialize_array(sequence_t, sequence_length); + } + catch (exception::Exception& ex) + { + free(sequence_t); + sequence_t = NULL; + set_state(state_before_error); + ex.raise(); + } + + num_elements = sequence_length; + return *this; + } + + /*! + * @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 num_elements 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& deserialize_sequence( + _T*& sequence_t, + size_t& num_elements, + Endianness endianness) + { + bool aux_swap = swap_bytes_; + swap_bytes_ = (swap_bytes_ && (static_cast(endianness_) == endianness)) || + (!swap_bytes_ && (static_cast(endianness_) != endianness)); + + try + { + deserialize_sequence(sequence_t, num_elements); + swap_bytes_ = aux_swap; + } + catch (exception::Exception& ex) + { + swap_bytes_ = aux_swap; + 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 num_elements 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_SPEC + Cdr& deserialize_sequence( + std::string*& sequence_t, + size_t& num_elements) + { + return deserialize_string_sequence(sequence_t, num_elements); + } + + /*! + * @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 num_elements 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_SPEC + Cdr& deserialize_sequence( + std::wstring*& sequence_t, + size_t& num_elements) + { + return deserialize_wstring_sequence(sequence_t, num_elements); + } + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /// XCDR extensions + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + + /*! + * @brief Encodes a member of a type according to the encoding algorithm used. + * @param[in] member_id Member identifier. + * @param[in] member_value Member value. + * @param[in] header_selection Selects which member header will be used to allocate space. + * Default: XCdrHeaderSelection::AUTO_WITH_SHORT_HEADER_BY_DEFAULT. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& serialize_member( + const MemberId& member_id, + const _T& member_value, + XCdrHeaderSelection header_selection = XCdrHeaderSelection::AUTO_WITH_SHORT_HEADER_BY_DEFAULT) + { + Cdr::state current_state(*this); + (this->*begin_serialize_member_)(member_id, true, current_state, header_selection); + serialize(member_value); + return (this->*end_serialize_member_)(current_state); + } + + /*! + * @brief Encodes an optional member of a type according to the encoding algorithm used. + * @param[in] member_id Member identifier. + * @param[in] member_value Optional member value. + * @param[in] header_selection Selects which member header will be used to allocate space. + * Default: XCdrHeaderSelection::AUTO_WITH_SHORT_HEADER_BY_DEFAULT. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& serialize_member( + const MemberId& member_id, + const optional<_T>& member_value, + XCdrHeaderSelection header_selection = XCdrHeaderSelection::AUTO_WITH_SHORT_HEADER_BY_DEFAULT) + { + Cdr::state current_state(*this); + (this->*begin_serialize_opt_member_)(member_id, member_value.has_value(), current_state, header_selection); + serialize(member_value); + return (this->*end_serialize_opt_member_)(current_state); + } + + /*! + * @brief Decodes a member of a type according to the encoding algorithm used. + * @param[out] member_value A reference of the variable where the member value will be stored. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& deserialize_member( + _T& member_value) + { + return deserialize(member_value); + } + + /*! + * @brief Decodes an optional member of a type according to the encoding algorithm used. + * @param[out] member_value A reference of the variable where the optional member value will be stored. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& deserialize_member( + optional<_T>& member_value) + { + if (EncodingAlgorithmFlag::PLAIN_CDR == current_encoding_) + { + Cdr::state current_state(*this); + MemberId member_id; + xcdr1_deserialize_member_header(member_id, current_state); + auto prev_offset = offset_; + if (0 < current_state.member_size_) + { + deserialize(member_value); + } + size_t member_size {current_state.member_size_}; + size_t diff {offset_ - prev_offset}; + if (member_size < diff) + { + throw exception::BadParamException( + "Member size provided by member header is lower than real decoded member size"); + } + + // Skip unused bytes + offset_ += (member_size - diff); + } + else + { + deserialize(member_value); + } + return *this; + } + + /*! + * @brief Tells to the encoder a new type and its members starts to be encoded. + * @param[in,out] current_state State of the encoder previous of calling this function. + * @param[in] type_encoding The encoding algorithm used to encode the type and its members. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + Cdr_DllAPI Cdr& begin_serialize_type( + Cdr::state& current_state, + EncodingAlgorithmFlag type_encoding); + + /*! + * @brief Tells to the encoder the encoding of the type finishes. + * @param[in] current_state State of the encoder previous of calling the function begin_serialize_type. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + Cdr_DllAPI Cdr& end_serialize_type( + Cdr::state& current_state); + + /*! + * @brief Tells to the encoder a new type and its members starts to be decoded. + * @param[in] type_encoding The encoding algorithm used to decode the type and its members. + * @param[in] functor Functor called each time a member has to be decoded. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + Cdr_DllAPI Cdr& deserialize_type( + EncodingAlgorithmFlag type_encoding, + std::function functor); + + /*! + * @brief Encodes an optional in the buffer. + * @param[in] value A reference to the optional which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& serialize( + const optional<_T>& value) + { + if (CdrVersion::XCDRv2 == cdr_version_ && EncodingAlgorithmFlag::PL_CDR2 != current_encoding_) + { + serialize(value.has_value()); + } + + if (value.has_value()) + { + serialize(*value); + } + return *this; + } + + /*! + * @brief Encodes an external in the buffer. + * @param[in] value A reference to the external which will be encoded in the buffer. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::BadParamException This exception is thrown when external is null. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& serialize( + const external<_T>& value) + { + if (!value) + { + throw exception::BadParamException("External member is null"); + } + + serialize(*value); + return *this; + } + + /*! + * @brief Tells the encoder the member identifier for the next member to be encoded. + * @param[in] member_id Member identifier. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::BadParamException This exception is thrown when a member id is already set without being + * encoded. + */ + Cdr_DllAPI Cdr& operator <<( + const MemberId& member_id); + + /*! + * @brief Decodes an optional from the buffer. + * @param[out] value A reference to the variable where the optional will be stored. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& deserialize( + optional<_T>& value) + { + bool is_present = true; + if (CdrVersion::XCDRv2 == cdr_version_ && EncodingAlgorithmFlag::PL_CDR2 != current_encoding_) + { + deserialize(is_present); + } + value.reset(is_present); + if (is_present) + { + deserialize(*value); + } + return *this; + } + + /*! + * @brief Decodes an external from the buffer. + * @param[out] value A reference to the variable where the external will be stored. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::BadParamException This exception is thrown when the external is locked. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& deserialize( + external<_T>& value) + { + if (value.is_locked()) + { + throw exception::BadParamException("External member is locked"); + } + + if (!value) + { + value = external<_T>{new typename external<_T>::type()}; + } + + deserialize(*value); + return *this; + } + + /*! + * @brief Decodes an optional of an external from the buffer. + * @param[out] value A reference to the variable where the optional will be stored. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::BadParamException This exception is thrown when the external is locked. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + */ + template + Cdr& deserialize( + optional>& value) + { + if (value.has_value() && value.value().is_locked()) + { + throw exception::BadParamException("External member is locked"); + } + + bool is_present = true; + if (CdrVersion::XCDRv2 == cdr_version_ && EncodingAlgorithmFlag::PL_CDR2 != current_encoding_) + { + deserialize(is_present); + } + value.reset(is_present); + if (is_present) + { + deserialize(*value); + } + return *this; + } + + /*! + * @brief Encodes an empty DHEADER if the encoding version is XCDRv2. + * After serializing the members's type, @ref set_xcdrv2_dheader must be called to set the correct DHEADER value + * using the @ref state returned by this function. + */ + Cdr_DllAPI state allocate_xcdrv2_dheader(); + + /*! + * @brief Uses the @ref state to calculate the member's type size and serialize the value in the previous allocated + * DHEADER. + * + * @param[in] state @ref state used to calculate the member's type size. + */ + Cdr_DllAPI void set_xcdrv2_dheader( + const state& state); + +private: + + Cdr( + const Cdr&) = delete; + + Cdr& operator =( + const Cdr&) = delete; + + Cdr_DllAPI Cdr& serialize_bool_array( + const std::vector& vector_t); + + Cdr_DllAPI Cdr& serialize_bool_sequence( + const std::vector& vector_t); + + Cdr_DllAPI Cdr& deserialize_bool_array( + std::vector& vector_t); + + Cdr_DllAPI Cdr& deserialize_bool_sequence( + std::vector& vector_t); + + Cdr_DllAPI Cdr& deserialize_string_sequence( + std::string*& sequence_t, + size_t& num_elements); + + Cdr_DllAPI Cdr& deserialize_wstring_sequence( + std::wstring*& sequence_t, + size_t& num_elements); + + /*! + * @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 num_elements 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& serialize_array( + const std::array<_T, _Size>* array_t, + size_t num_elements) + { + return serialize_array(array_t->data(), num_elements * array_t->size()); + } + + /*! + * @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 num_elements 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& deserialize_array( + std::array<_T, _Size>* array_t, + size_t num_elements) + { + return deserialize_array(array_t->data(), num_elements * 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 num_elements Number of the elements in the array. + * @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& deserialize_array( + std::array<_T, _Size>* array_t, + size_t num_elements, + Endianness endianness) + { + return deserialize_array(array_t->data(), num_elements * array_t->size(), endianness); + } + + /*! + * @brief Returns the number of bytes needed to align the current position (having as reference the origin) to + * certain data size. + * @param data_size The size of the data that will be serialized. + * @return The size needed for the alignment. + */ + inline size_t alignment( + size_t data_size) const + { + return data_size > last_data_size_ ? (data_size - ((offset_ - origin_) % data_size)) & (data_size - 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 make_alignment( + size_t align) + { + offset_ += align; + last_data_size_ = 0; + } + + /*! + * @brief This function resizes the internal buffer. It only applies if the FastBuffer object was created with the default constructor. + * @param min_size_inc Minimun size increase for the internal buffer + * @return True if the resize was succesful, false if it was not + */ + bool resize( + size_t min_size_inc); + + Cdr_DllAPI const char* read_string( + uint32_t& length); + Cdr_DllAPI const std::wstring read_wstring( + uint32_t& length); + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /// XCDR extensions + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /*! + * @brief Encodes a short member header of a member according to XCDRv1. + * @param[in] member_id Member identifier. + * @pre Member identifier less than 0x3F00. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr1_serialize_short_member_header( + const MemberId& member_id); + + /*! + * @brief Finish the encoding of a short member header of a member according to XCDRv1. + * @param[in] member_id Member identifier. + * @pre Member identifier less than 0x3F00. + * @param[in] member_serialized_size Size of the serialized member. + * @pre Serialized size equal or less than 0xFFFF. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr1_end_short_member_header( + const MemberId& member_id, + size_t member_serialized_size); + + /*! + * @brief Encodes a long member header of a member according to XCDRv1. + * @param[in] member_id Member identifier. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr1_serialize_long_member_header( + const MemberId& member_id); + + /*! + * @brief Finish the encoding of a long member header of a member according to XCDRv1. + * @param[in] member_id Member identifier. + * @param[in] member_serialized_size Size of the serialized member. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr1_end_long_member_header( + const MemberId& member_id, + size_t member_serialized_size); + + /*! + * @brief Changes the previous encoded long header to a short header according to XCDRv1. + * @param[in] member_id Member identifier. + * @pre Member identifier less than 0x3F00. + * @param[in] member_serialized_size Size of the serialized member. + * @pre Serialized size equal or less than 0xFFFF. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr1_change_to_short_member_header( + const MemberId& member_id, + size_t member_serialized_size); + + /*! + * @brief Changes the previous encoded short header to a long header according to XCDRv1. + * @param[in] member_id Member identifier. + * @param[in] member_serialized_size Size of the serialized member. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr1_change_to_long_member_header( + const MemberId& member_id, + size_t member_serialized_size); + + /*! + * @brief Decodes a member header according to XCDRv1. + * @param[out] member_id Member identifier. + * @param[in,out] current_state State of the encoder previous to call this function. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to decode an invalid value. + */ + Cdr_DllAPI bool xcdr1_deserialize_member_header( + MemberId& member_id, + Cdr::state& current_state); + + /*! + * @brief Encodes a short member header of a member according to XCDRv2. + * @param[in] member_id Member identifier. + * @pre Member identifier less than 0x10000000. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr2_serialize_short_member_header( + const MemberId& member_id); + + /*! + * @brief Finish the encoding of a short member header of a member according to XCDRv2. + * @param[in] member_id Member identifier. + * @pre Member identifier less than 0x10000000. + * @param[in] member_serialized_size Size of the serialized member. + * @pre Serialized size equal or less than 0x8. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr2_end_short_member_header( + const MemberId& member_id, + size_t member_serialized_size); + + /*! + * @brief Encodes a long member header of a member according to XCDRv2. + * @param[in] member_id Member identifier. + * @pre Member identifier less than 0x10000000. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr2_serialize_long_member_header( + const MemberId& member_id); + + /*! + * @brief Finish the encoding of a long member header of a member according to XCDRv2. + * @param[in] member_id Member identifier. + * @pre Member identifier less than 0x10000000. + * @param[in] member_serialized_size Size of the serialized member. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr2_end_long_member_header( + const MemberId& member_id, + size_t member_serialized_size); + + /*! + * @brief Changes the previous encoded long header to a short header according to XCDRv2. + * @param[in] member_id Member identifier. + * @pre Member identifier less than 0x10000000. + * @param[in] member_serialized_size Size of the serialized member. + * @pre Serialized size equal or less than 8. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr2_change_to_short_member_header( + const MemberId& member_id, + size_t member_serialized_size); + + /*! + * @brief Changes the previous encoded long header to a short header according to XCDRv2. + * @param[in] member_id Member identifier. + * @pre Member identifier less than 0x10000000. + * @param[in] member_serialized_size Size of the serialized member. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr2_change_to_long_member_header( + const MemberId& member_id, + size_t member_serialized_size); + + /*! + * @brief Join the previous encoded long header with the next DHEADER which was serialized after. + * @param[in] member_id Member identifier. + * @pre Member identifier less than 0x10000000. + * @param[in] offset The last offset of the buffer previous to call this function. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + void xcdr2_shrink_to_long_member_header( + const MemberId& member_id, + const FastBuffer::iterator& offset); + + /*! + * @brief Decodes a member header according to XCDRv2. + * @param[out] member_id Member identifier. + * @param[in,out] current_state State of the encoder previous to call this function. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to decode from a buffer + * position that exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to decode an invalid value. + */ + void xcdr2_deserialize_member_header( + MemberId& member_id, + Cdr::state& current_state); + + /*! + * @brief Tells to the encoder a member starts to be encoded according to XCDRv1. + * @param[in] member_id Member identifier. + * @pre Member identifier cannot be MEMBER_ID_INVALID and next_member_id_ must be equal to the member identifier or + * MEMBER_ID_INVALID. + * @param[in] is_present If the member is present. + * @pre When XCDRv1, is_present must be always true. + * @param[in,out] current_state State of the encoder previous to call this function. + * @pre Current encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR or EncodingAlgorithmFlag::PL_CDR. + * @param[in] header_selection Selects which member header will be used to allocate space. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to encode a long header when + * header_selection is XCdrHeaderSelection::SHORT_HEADER. + */ + Cdr& xcdr1_begin_serialize_member( + const MemberId& member_id, + bool is_present, + Cdr::state& current_state, + XCdrHeaderSelection header_selection); + + /*! + * @brief Tells to the encoder to finish the encoding of the member. + * @param[in] current_state State of the encoder previous to call xcdr1_begin_serialize_member function. + * @pre next_member_id_ cannot be MEMBER_ID_INVALID. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to encode a long header when + * header_selection is XCdrHeaderSelection::SHORT_HEADER. + */ + Cdr& xcdr1_end_serialize_member( + const Cdr::state& current_state); + + /*! + * @brief Tells to the encoder a member starts to be encoded according to XCDRv1. + * @param[in] member_id Member identifier. + * @pre Member identifier cannot be MEMBER_ID_INVALID and next_member_id_ must be equal to the member identifier or + * MEMBER_ID_INVALID. + * @param[in] is_present If the member is present. + * @param[in,out] current_state State of the encoder previous to call this function. + * @pre Current encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR or EncodingAlgorithmFlag::PL_CDR. + * @param[in] header_selection Selects which member header will be used to allocate space. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to encode a long header when + * header_selection is XCdrHeaderSelection::SHORT_HEADER. + */ + Cdr& xcdr1_begin_serialize_opt_member( + const MemberId& member_id, + bool is_present, + Cdr::state& current_state, + XCdrHeaderSelection header_selection); + + /*! + * @brief Tells to the encoder to finish the encoding of the member. + * @param[in] current_state State of the encoder previous to call xcdr1_begin_serialize_opt_member function. + * @pre next_member_id_ cannot be MEMBER_ID_INVALID. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to encode a long header when + * header_selection is XCdrHeaderSelection::SHORT_HEADER. + */ + Cdr& xcdr1_end_serialize_opt_member( + const Cdr::state& current_state); + + /*! + * @brief Tells to the encoder a member starts to be encoded according to XCDRv2. + * @param[in] member_id Member identifier. + * @pre Member identifier cannot be MEMBER_ID_INVALID and next_member_id_ must be equal to the member identifier or + * MEMBER_ID_INVALID. + * @param[in] is_present If the member is present. + * @param[in,out] current_state State of the encoder previous to call this function. + * @pre Current encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR2, EncodingAlgorithmFlag::DELIMIT_CDR2 or + * EncodingAlgorithmFlag::PL_CDR2. + * @param[in] header_selection Selects which member header will be used to allocate space. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to encode member identifier equal or + * greater than 0x10000000. + */ + Cdr& xcdr2_begin_serialize_member( + const MemberId& member_id, + bool is_present, + Cdr::state& current_state, + XCdrHeaderSelection header_selection); + + /*! + * @brief Tells to the encoder to finish the encoding of the member. + * @param[in] current_state State of the encoder previous to call xcdr2_begin_serialize_member function. + * @pre next_member_id_ cannot be MEMBER_ID_INVALID. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when trying to encode a long header when + * header_selection is XCdrHeaderSelection::SHORT_HEADER. + */ + Cdr& xcdr2_end_serialize_member( + const Cdr::state& current_state); + + /*! + * @brief Tells to the encoder a new type and its members start to be encoded according to XCDRv1. + * @param[in,out] current_state State of the encoder previous to call this function. + * @pre Current encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR or EncodingAlgorithmFlag::PL_CDR. + * @param[in] type_encoding Encoding algorithm used to encode the type and its members. + * @pre Type encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR or EncodingAlgorithmFlag::PL_CDR. + * @pre If it is the beginning of the whole encoding, current encoding must be equal to type encoding. + * @return Reference to the eprosima::fastcdr::Cdr object. + */ + Cdr& xcdr1_begin_serialize_type( + Cdr::state& current_state, + EncodingAlgorithmFlag type_encoding) noexcept; + + /*! + * @brief Tells to the encoder to finish the encoding of the type. + * @param[in] current_state State of the encoder previous to call xcdr1_begin_serialize_type function. + * @pre Current encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR or EncodingAlgorithmFlag::PL_CDR. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + Cdr& xcdr1_end_serialize_type( + const Cdr::state& current_state); + + /*! + * @brief Tells to the encoder a new type and its members start to be encoded according to XCDRv2. + * @param[in,out] current_state State of the encoder previous to call this function. + * @pre Current encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR2, EncodingAlgorithmFlag::DELIMIT_CDR2 or + * EncodingAlgorithmFlag::PL_CDR2. + * @param[in] type_encoding Encoding algorithm used to encode the type and its members. + * @pre Type encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR2, EncodingAlgorithmFlag::DELIMIT_CDR2 or + * EncodingAlgorithmFlag::PL_CDR2. + * @pre If it is the beginning of the whole encoding, current encoding must be equal to type encoding. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + Cdr& xcdr2_begin_serialize_type( + Cdr::state& current_state, + EncodingAlgorithmFlag type_encoding); + + /*! + * @brief Tells to the encoder to finish the encoding of the type. + * @param[in] current_state State of the encoder previous to call xcdr2_begin_serialize_type function. + * @pre Current encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR2, EncodingAlgorithmFlag::DELIMIT_CDR2 or + * EncodingAlgorithmFlag::PL_CDR2. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + */ + Cdr& xcdr2_end_serialize_type( + const Cdr::state& current_state); + + /*! + * @brief Tells to the encoder a new type and its members start to be decoded according to XCDRv1. + * @param[in] type_encoding Encoding algorithm used to encode the type and its members. + * @pre Type encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR or EncodingAlgorithmFlag::PL_CDR. + * @pre If it is the beginning of the whole encoding, current encoding must be equal to type encoding. + * @param[in] functor Functor called each time a member has to be decoded. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when an incorrect behaviour happens when + * trying to decode. + */ + Cdr& xcdr1_deserialize_type( + EncodingAlgorithmFlag type_encoding, + std::function functor); + + /*! + * @brief Tells to the encoder a new type and its members start to be decoded according to XCDRv2. + * @param[in] type_encoding Encoding algorithm used to encode the type and its members. + * @pre Type encoding algorithm must be EncodingAlgorithmFlag::PLAIN_CDR2, EncodingAlgorithmFlag::DELIMIT_CDR2 or + * EncodingAlgorithmFlag::PL_CDR2. + * @pre If it is the beginning of the whole encoding, current encoding must be equal to type encoding. + * @param[in] functor Functor called each time a member has to be decoded. + * @return Reference to the eprosima::fastcdr::Cdr object. + * @exception exception::NotEnoughMemoryException This exception is thrown when trying to encode into a buffer + * position that exceeds the internal memory size. + * @exception exception::BadParamException This exception is thrown when an incorrect behaviour happens when + * trying to decode. + */ + Cdr& xcdr2_deserialize_type( + EncodingAlgorithmFlag type_encoding, + std::function functor); + + Cdr& cdr_begin_serialize_member( + const MemberId& member_id, + bool is_present, + Cdr::state& current_state, + XCdrHeaderSelection header_selection); + + Cdr& cdr_end_serialize_member( + const Cdr::state& current_state); + + Cdr& cdr_begin_serialize_type( + Cdr::state& current_state, + EncodingAlgorithmFlag type_encoding); + + Cdr& cdr_end_serialize_type( + const Cdr::state& current_state); + + Cdr& cdr_deserialize_type( + EncodingAlgorithmFlag type_encoding, + std::function functor); + + /*! + * @brief Resets the internal callbacks depending on the current selected Cdr version. + */ + void reset_callbacks(); + + using begin_serialize_member_functor = Cdr& (Cdr::*)( + const MemberId&, + bool, + Cdr::state&, + XCdrHeaderSelection); + begin_serialize_member_functor begin_serialize_member_ { nullptr }; + + using end_serialize_member_functor = Cdr& (Cdr::*)( + const Cdr::state&); + end_serialize_member_functor end_serialize_member_ { nullptr }; + + using begin_serialize_opt_member_functor = Cdr& (Cdr::*)( + const MemberId&, + bool, + Cdr::state&, + XCdrHeaderSelection); + begin_serialize_opt_member_functor begin_serialize_opt_member_ { nullptr }; + + using end_serialize_memberopt__functor = Cdr& (Cdr::*)( + const Cdr::state&); + end_serialize_member_functor end_serialize_opt_member_ { nullptr }; + + using begin_serialize_type_functor = Cdr& (Cdr::*)( + Cdr::state&, + EncodingAlgorithmFlag); + begin_serialize_type_functor begin_serialize_type_ { nullptr }; + + using end_serialize_type_functor = Cdr& (Cdr::*)( + const Cdr::state&); + end_serialize_type_functor end_serialize_type_ { nullptr }; + + using deserialize_type_functor = Cdr& (Cdr::*)( + EncodingAlgorithmFlag, + std::function); + deserialize_type_functor deserialize_type_ { nullptr }; + + //! @brief Reference to the buffer that will be serialized/deserialized. + FastBuffer& cdr_buffer_; + + //! @brief The type of CDR that will be use in serialization/deserialization. + CdrVersion cdr_version_ {CdrVersion::XCDRv2}; + + //! @brief Stores the main encoding algorithm. + EncodingAlgorithmFlag encoding_flag_ {EncodingAlgorithmFlag::PLAIN_CDR2}; + + //! @brief Stores the current encoding algorithm. + EncodingAlgorithmFlag current_encoding_ {EncodingAlgorithmFlag::PLAIN_CDR2}; + + //! @brief This attribute stores the option flags when the CDR type is DDS_CDR; + std::array options_{{0}}; + + //! @brief The endianness that will be applied over the buffer. + uint8_t endianness_ {Endianness::LITTLE_ENDIANNESS}; + + //! @brief This attribute specifies if it is needed to swap the bytes. + bool swap_bytes_ {false}; + + //! @brief Stores the last datasize serialized/deserialized. It's used to optimize. + size_t last_data_size_ {0}; + + //! @brief The current position in the serialization/deserialization process. + FastBuffer::iterator offset_; + + //! @brief The position from where the alignment is calculated. + FastBuffer::iterator origin_; + + //! @brief The last position in the buffer; + FastBuffer::iterator end_; + + //! Next member identifier to be processed. + MemberId next_member_id_; + + //! Align for types equal or greater than 64bits. + size_t align64_ {4}; + + /*! + * When serializing a member's type using XCDRv2, this enumerator is used to inform the type was serialized with a + * DHEADER and the algorithm could optimize the XCDRv2 member header. + */ + enum SerializedMemberSizeForNextInt + { + NO_SERIALIZED_MEMBER_SIZE, //! Default. No serialized member size in a DHEADER. + SERIALIZED_MEMBER_SIZE, //! Serialized member size in a DHEADER. + SERIALIZED_MEMBER_SIZE_4, //! Serialized member size (which is a multiple of 4) in a DHEADER. + SERIALIZED_MEMBER_SIZE_8 //! Serialized member size (which is a multiple of 8) in a DHEADER. + } + //! Specifies if a DHEADER was serialized. Used to optimize XCDRv2 member headers. + serialized_member_size_ {NO_SERIALIZED_MEMBER_SIZE}; + + //! Stores the initial state. + state initial_state_; + + //! Whether the encapsulation was serialized. + bool encapsulation_serialized_ {false}; + + + uint32_t get_long_lc( + SerializedMemberSizeForNextInt serialized_member_size); + + uint32_t get_short_lc( + size_t member_serialized_size); + + template::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + constexpr SerializedMemberSizeForNextInt get_serialized_member_size() const + { + return (1 == sizeof(_T) ? SERIALIZED_MEMBER_SIZE : + (4 == sizeof(_T) ? SERIALIZED_MEMBER_SIZE_4 : + (8 == sizeof(_T) ? SERIALIZED_MEMBER_SIZE_8 : NO_SERIALIZED_MEMBER_SIZE))); + } + +}; + +} //namespace fastcdr +} //namespace eprosima + +#endif // _CDR_CDR_H_ diff --git a/LibCarla/source/carla/ros2/fastdds/fastcdr/CdrSizeCalculator.hpp b/LibCarla/source/carla/ros2/fastdds/fastcdr/CdrSizeCalculator.hpp new file mode 100644 index 00000000000..c49799a2fbd --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/fastcdr/CdrSizeCalculator.hpp @@ -0,0 +1,1347 @@ +// Copyright 2023 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT 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_CDRSIZECALCULATOR_HPP_ +#define _FASTCDR_CDRSIZECALCULATOR_HPP_ + +#include +#include +#include +#include +#include +#include + +#include "fastcdr/fastcdr_dll.h" + +#include "fastcdr/CdrEncoding.hpp" +#include "fastcdr/cdr/fixed_size_string.hpp" +#include "fastcdr/detail/container_recursive_inspector.hpp" +#include "fastcdr/exceptions/BadParamException.h" +#include "fastcdr/xcdr/external.hpp" +#include "fastcdr/xcdr/MemberId.hpp" +#include "fastcdr/xcdr/optional.hpp" + +namespace eprosima { +namespace fastcdr { + +class CdrSizeCalculator; + +template +extern size_t calculate_serialized_size( + CdrSizeCalculator&, + const _T&, + size_t&); + +/*! + * @brief This class offers an interface to calculate the encoded size of a type serialized using a support encoding + * algorithm. + * @ingroup FASTCDRAPIREFERENCE + */ +class CdrSizeCalculator +{ +public: + + /*! + * @brief Constructor. + * @param[in] cdr_version Represents the version of the encoding algorithm that will be used for the encoding. + * The default value is CdrVersion::XCDRv2. + */ + Cdr_DllAPI CdrSizeCalculator( + CdrVersion cdr_version); + + /*! + * @brief Constructor. + * @param[in] cdr_version Represents the version of the encoding algorithm that will be used for the encoding. + * The default value is CdrVersion::XCDRv2. + * @param[in] encoding Represents the initial encoding. + */ + Cdr_DllAPI CdrSizeCalculator( + CdrVersion cdr_version, + EncodingAlgorithmFlag encoding); + + /*! + * @brief Retrieves the version of the encoding algorithm used by the instance. + * @return Configured CdrVersion. + */ + Cdr_DllAPI CdrVersion get_cdr_version() const; + + /*! + * @brief Retrieves the current encoding algorithm used by the instance. + * @return Configured EncodingAlgorithmFlag. + */ + Cdr_DllAPI EncodingAlgorithmFlag get_encoding() const; + + /*! + * @brief Generic template which calculates the encoded size of an instance of an unknown type. + * @tparam _T Instance's type. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value>::type* = nullptr, typename = void> + size_t calculate_serialized_size( + const _T& data, + size_t& current_alignment) + { + return eprosima::fastcdr::calculate_serialized_size(*this, data, current_alignment); + } + + /*! + * @brief Template which calculates the encoded size of an instance of an enumeration of 32bits. + * @tparam _T Instance's type. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + int32_t>::value>::type* = nullptr> + size_t calculate_serialized_size( + const _T& data, + size_t& current_alignment) + { + return calculate_serialized_size(static_cast(data), current_alignment); + } + + /*! + * @brief Template which calculates the encoded size of an instance of an enumeration of unsigned 32bits. + * @tparam _T Instance's type. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + uint32_t>::value>::type* = nullptr> + size_t calculate_serialized_size( + const _T& data, + size_t& current_alignment) + { + return calculate_serialized_size(static_cast(data), current_alignment); + } + + /*! + * @brief Template which calculates the encoded size of an instance of an enumeration of 16bits. + * @tparam _T Instance's type. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + int16_t>::value>::type* = nullptr> + size_t calculate_serialized_size( + const _T& data, + size_t& current_alignment) + { + return calculate_serialized_size(static_cast(data), current_alignment); + } + + /*! + * @brief Template which calculates the encoded size of an instance of an enumeration of unsigned 16bits. + * @tparam _T Instance's type. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + uint16_t>::value>::type* = nullptr> + size_t calculate_serialized_size( + const _T& data, + size_t& current_alignment) + { + return calculate_serialized_size(static_cast(data), current_alignment); + } + + /*! + * @brief Template which calculates the encoded size of an instance of an enumeration of 8bits. + * @tparam _T Instance's type. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + int8_t>::value>::type* = nullptr> + size_t calculate_serialized_size( + const _T& data, + size_t& current_alignment) + { + return calculate_serialized_size(static_cast(data), current_alignment); + } + + /*! + * @brief Template which calculates the encoded size of an instance of an enumeration of unsigned 8bits. + * @tparam _T Instance's type. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value>::type* = nullptr, + typename std::enable_if::type, + uint8_t>::value>::type* = nullptr> + size_t calculate_serialized_size( + const _T& data, + size_t& current_alignment) + { + return calculate_serialized_size(static_cast(data), current_alignment); + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an int8_t. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const int8_t& data, + size_t& current_alignment) + { + static_cast(data); + ++current_alignment; + return 1; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an uint8_t. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const uint8_t& data, + size_t& current_alignment) + { + static_cast(data); + ++current_alignment; + return 1; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a char. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const char& data, + size_t& current_alignment) + { + static_cast(data); + ++current_alignment; + return 1; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a bool. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const bool& data, + size_t& current_alignment) + { + static_cast(data); + ++current_alignment; + return 1; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a wchar. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const wchar_t& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {2 + alignment(current_alignment, 2)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a int16_t. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const int16_t& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {2 + alignment(current_alignment, 2)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a uint16_t. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const uint16_t& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {2 + alignment(current_alignment, 2)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a int32_t. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const int32_t& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {4 + alignment(current_alignment, 4)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a uint32_t. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const uint32_t& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {4 + alignment(current_alignment, 4)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a int64_t. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const int64_t& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {8 + alignment(current_alignment, align64_)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a uint64_t. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const uint64_t& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {8 + alignment(current_alignment, align64_)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a float. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const float& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {4 + alignment(current_alignment, 4)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a double. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const double& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {8 + alignment(current_alignment, align64_)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a long double. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const long double& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {16 + alignment(current_alignment, align64_)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a std::string. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const std::string& data, + size_t& current_alignment) + { + size_t calculated_size {4 + alignment(current_alignment, 4) + data.size() + 1}; + current_alignment += calculated_size; + serialized_member_size_ = SERIALIZED_MEMBER_SIZE; + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a std::wstring. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const std::wstring& data, + size_t& current_alignment) + { + size_t calculated_size {4 + alignment(current_alignment, 4) + data.size() * 2}; + current_alignment += calculated_size; + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a fixed_string. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template + size_t calculate_serialized_size( + const fixed_string& data, + size_t& current_alignment) + { + size_t calculated_size {4 + alignment(current_alignment, 4) + data.size() + 1}; + current_alignment += calculated_size; + serialized_member_size_ = SERIALIZED_MEMBER_SIZE; + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a sequence of non-primitives. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value && + !std::is_arithmetic<_T>::value>::type* = nullptr> + size_t calculate_serialized_size( + const std::vector<_T, _Alloc>& data, + size_t& current_alignment) + { + size_t initial_alignment {current_alignment}; + + if (CdrVersion::XCDRv2 == cdr_version_) + { + // DHEADER + current_alignment += 4 + alignment(current_alignment, 4); + } + + current_alignment += 4 + alignment(current_alignment, 4); + + size_t calculated_size {current_alignment - initial_alignment}; + calculated_size += calculate_array_serialized_size(data.data(), data.size(), current_alignment); + + if (CdrVersion::XCDRv2 == cdr_version_) + { + // Inform DHEADER can be joined with NEXTINT + serialized_member_size_ = SERIALIZED_MEMBER_SIZE; + } + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a sequence of primitives. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + size_t calculate_serialized_size( + const std::vector<_T, _Alloc>& data, + size_t& current_alignment) + { + size_t initial_alignment {current_alignment}; + + current_alignment += 4 + alignment(current_alignment, 4); + + size_t calculated_size {current_alignment - initial_alignment}; + calculated_size += calculate_array_serialized_size(data.data(), data.size(), current_alignment); + + if (CdrVersion::XCDRv2 == cdr_version_) + { + serialized_member_size_ = get_serialized_member_size<_T>(); + } + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a sequence of bool. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_serialized_size( + const std::vector& data, + size_t& current_alignment) + { + size_t calculated_size {data.size() + 4 + alignment(current_alignment, 4)}; + current_alignment += calculated_size; + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template + size_t calculate_serialized_size( + const std::array<_T, _Size>& data, + size_t& current_alignment) + { + size_t initial_alignment {current_alignment}; + + if (CdrVersion::XCDRv2 == cdr_version_ && + !is_multi_array_primitive(&data)) + { + // DHEADER + current_alignment += 4 + alignment(current_alignment, 4); + } + + size_t calculated_size {current_alignment - initial_alignment}; + calculated_size += calculate_array_serialized_size(data.data(), data.size(), current_alignment); + + if (CdrVersion::XCDRv2 == cdr_version_ && + !is_multi_array_primitive(&data)) + { + // Inform DHEADER can be joined with NEXTINT + serialized_member_size_ = SERIALIZED_MEMBER_SIZE; + } + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a map of non-primitives. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value && + !std::is_arithmetic<_V>::value>::type* = nullptr> + size_t calculate_serialized_size( + const std::map<_K, _V>& data, + size_t& current_alignment) + { + size_t initial_alignment {current_alignment}; + + if (CdrVersion::XCDRv2 == cdr_version_) + { + // DHEADER + current_alignment += 4 + alignment(current_alignment, 4); + } + + current_alignment += 4 + alignment(current_alignment, 4); + + size_t calculated_size {current_alignment - initial_alignment}; + for (auto it = data.begin(); it != data.end(); ++it) + { + calculated_size += calculate_serialized_size(it->first, current_alignment); + calculated_size += calculate_serialized_size(it->second, current_alignment); + } + + if (CdrVersion::XCDRv2 == cdr_version_) + { + // Inform DHEADER can be joined with NEXTINT + serialized_member_size_ = SERIALIZED_MEMBER_SIZE; + } + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a map of primitives. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value || + std::is_arithmetic<_V>::value>::type* = nullptr> + size_t calculate_serialized_size( + const std::map<_K, _V>& data, + size_t& current_alignment) + { + size_t initial_alignment {current_alignment}; + + current_alignment += 4 + alignment(current_alignment, 4); + + size_t calculated_size {current_alignment - initial_alignment}; + for (auto it = data.begin(); it != data.end(); ++it) + { + calculated_size += calculate_serialized_size(it->first, current_alignment); + calculated_size += calculate_serialized_size(it->second, current_alignment); + } + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a bitset of 8bits. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template ::type* = nullptr> + size_t calculate_serialized_size( + const std::bitset& data, + size_t& current_alignment) + { + static_cast(data); + ++current_alignment; + return 1; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a bitset of 16bits. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template ::type* = nullptr> + size_t calculate_serialized_size( + const std::bitset& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {2 + alignment(current_alignment, 2)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a bitset of 32bits. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template ::type* = nullptr> + size_t calculate_serialized_size( + const std::bitset& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {4 + alignment(current_alignment, 4)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a bitset of 64bits. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template ::type* = nullptr> + size_t calculate_serialized_size( + const std::bitset& data, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {8 + alignment(current_alignment, align64_)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an optional type. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template + size_t calculate_serialized_size( + const optional<_T>& data, + size_t& current_alignment) + { + size_t initial_alignment = current_alignment; + + if (CdrVersion::XCDRv2 == cdr_version_ && + EncodingAlgorithmFlag::PL_CDR2 != current_encoding_) + { + // Take into account the boolean is_present; + ++current_alignment; + } + + size_t calculated_size {current_alignment - initial_alignment}; + + if (data.has_value()) + { + calculated_size += calculate_serialized_size(data.value(), current_alignment); + } + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an external type. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @exception exception::BadParamException This exception is thrown when the external is null. + * @return Encoded size of the instance. + */ + template + size_t calculate_serialized_size( + const external<_T>& data, + size_t& current_alignment) + { + if (!data) + { + throw exception::BadParamException("External member is null"); + } + + return calculate_serialized_size(*data, current_alignment); + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of unknown type. + * @tparam _T Array's type. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template + size_t calculate_array_serialized_size( + const _T* data, + size_t num_elements, + size_t& current_alignment) + { + size_t calculated_size {0}; + + for (size_t count = 0; count < num_elements; ++count) + { + calculated_size += calculate_serialized_size(data[count], current_alignment); + } + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of int8_t. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const int8_t* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + current_alignment += num_elements; + return num_elements; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of uint8_t. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const uint8_t* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + current_alignment += num_elements; + return num_elements; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of char. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const char* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + current_alignment += num_elements; + return num_elements; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of wchar. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const wchar_t* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {num_elements* 2 + alignment(current_alignment, 2)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of int16_t. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const int16_t* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {num_elements* 2 + alignment(current_alignment, 2)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of uint16_t. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const uint16_t* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {num_elements* 2 + alignment(current_alignment, 2)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of int32_t. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const int32_t* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {num_elements* 4 + alignment(current_alignment, 4)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of uint32_t. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const uint32_t* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {num_elements* 4 + alignment(current_alignment, 4)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of int64_t. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const int64_t* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {num_elements* 8 + alignment(current_alignment, align64_)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of uint64_t. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const uint64_t* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {num_elements* 8 + alignment(current_alignment, align64_)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of float. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const float* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {num_elements* 4 + alignment(current_alignment, 4)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of double. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const double* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {num_elements* 8 + alignment(current_alignment, align64_)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of an array of long double. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const long double* data, + size_t num_elements, + size_t& current_alignment) + { + static_cast(data); + size_t calculated_size {num_elements* 16 + alignment(current_alignment, align64_)}; + current_alignment += calculated_size; + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an instance of a multi-dimensional array. + * @param[in] data Reference to the array's instance. + * @param[in] num_elements Number of elements in the array. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template + size_t calculate_array_serialized_size( + const std::array<_T, _N>* data, + size_t num_elements, + size_t& current_alignment) + { + return calculate_array_serialized_size(data->data(), num_elements * data->size(), current_alignment); + } + + /*! + * @brief Specific template which calculates the encoded size of an std::vector of primitives as an array. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + size_t calculate_array_serialized_size( + const std::vector<_T, _Alloc>& data, + size_t& current_alignment) + { + return calculate_array_serialized_size(data.data(), data.size(), current_alignment); + } + + /*! + * @brief Specific template which calculates the encoded size of an std::vector of non-primitives as an array. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + template::value && + !std::is_arithmetic<_T>::value>::type* = nullptr> + size_t calculate_array_serialized_size( + const std::vector<_T, _Alloc>& data, + size_t& current_alignment) + { + size_t initial_alignment {current_alignment}; + + if (CdrVersion::XCDRv2 == cdr_version_) + { + // DHEADER + current_alignment += 4 + alignment(current_alignment, 4); + } + + size_t calculated_size {current_alignment - initial_alignment}; + calculated_size += calculate_array_serialized_size(data.data(), data.size(), current_alignment); + + if (CdrVersion::XCDRv2 == cdr_version_) + { + // Inform DHEADER can be joined with NEXTINT + serialized_member_size_ = SERIALIZED_MEMBER_SIZE; + } + + return calculated_size; + } + + /*! + * @brief Specific template which calculates the encoded size of an std::vector of bool as an array. + * @param[in] data Reference to the instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the instance. + */ + TEMPLATE_SPEC + size_t calculate_array_serialized_size( + const std::vector& data, + size_t& current_alignment) + { + current_alignment += data.size(); + return data.size(); + } + + /*! + * @brief Generic template which calculates the encoded size of the constructed type's member of a unknown type. + * @tparam _T Member's type. + * @param[in] id Member's identifier. + * @param[in] data Reference to the member's instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the member's instance. + */ + template + size_t calculate_member_serialized_size( + const MemberId& id, + const _T& data, + size_t& current_alignment) + { + size_t initial_alignment {current_alignment}; + + if (EncodingAlgorithmFlag::PL_CDR == current_encoding_ || + EncodingAlgorithmFlag::PL_CDR2 == current_encoding_) + { + // Align to 4 for the XCDR header before calculating the data serialized size. + current_alignment += alignment(current_alignment, 4); + } + + size_t prev_size {current_alignment - initial_alignment}; + size_t extra_size {0}; + + if (EncodingAlgorithmFlag::PL_CDR == current_encoding_) + { + current_alignment = 0; + } + + size_t calculated_size {calculate_serialized_size(data, current_alignment)}; + + if (CdrVersion::XCDRv2 == cdr_version_ && EncodingAlgorithmFlag::PL_CDR2 == current_encoding_ && + 0 < calculated_size) + { + + if (8 < calculated_size || + (1 != calculated_size && 2 != calculated_size && 4 != calculated_size && + 8 != calculated_size)) + { + extra_size = 8; // Long EMHEADER. + if (NO_SERIALIZED_MEMBER_SIZE != serialized_member_size_) + { + calculated_size -= 4; // Join NEXTINT and DHEADER. + } + } + else + { + extra_size = 4; // EMHEADER; + } + } + else if (CdrVersion::XCDRv1 == cdr_version_ && EncodingAlgorithmFlag::PL_CDR == current_encoding_ && + 0 < calculated_size) + { + extra_size = 4; // ShortMemberHeader + + if (0x3F00 < id.id || calculated_size > std::numeric_limits::max()) + { + extra_size += 8; // LongMemberHeader + } + + } + + calculated_size += prev_size + extra_size; + if (EncodingAlgorithmFlag::PL_CDR != current_encoding_) + { + current_alignment += extra_size; + } + + serialized_member_size_ = NO_SERIALIZED_MEMBER_SIZE; + + return calculated_size; + } + + /*! + * @brief Generic template which calculates the encoded size of the constructed type's member of type optional. + * @tparam _T Member's optional type. + * @param[in] id Member's identifier. + * @param[in] data Reference to the member's instance. + * @param[inout] current_alignment Current alignment in the encoding. + * @return Encoded size of the member's instance. + */ + template + size_t calculate_member_serialized_size( + const MemberId& id, + const optional<_T>& data, + size_t& current_alignment) + { + size_t initial_alignment = current_alignment; + + if (CdrVersion::XCDRv2 != cdr_version_ || + EncodingAlgorithmFlag::PL_CDR2 == current_encoding_) + { + if (data.has_value() || EncodingAlgorithmFlag::PLAIN_CDR == current_encoding_) + { + // Align to 4 for the XCDR header before calculating the data serialized size. + current_alignment += alignment(current_alignment, 4); + } + } + + size_t prev_size = {current_alignment - initial_alignment}; + size_t extra_size {0}; + + if (CdrVersion::XCDRv1 == cdr_version_ && + (data.has_value() || EncodingAlgorithmFlag::PLAIN_CDR == current_encoding_)) + { + current_alignment = 0; + } + + size_t calculated_size {calculate_serialized_size(data, current_alignment)}; + + if (CdrVersion::XCDRv2 == cdr_version_ && EncodingAlgorithmFlag::PL_CDR2 == current_encoding_ && + 0 < calculated_size) + { + if (8 < calculated_size || + (1 != calculated_size && 2 != calculated_size && 4 != calculated_size && + 8 != calculated_size)) + { + extra_size = 8; // Long EMHEADER. + if (NO_SERIALIZED_MEMBER_SIZE != serialized_member_size_) + { + calculated_size -= 4; // Join NEXTINT and DHEADER. + } + } + else + { + extra_size = 4; // EMHEADER; + } + } + else if (CdrVersion::XCDRv1 == cdr_version_ && + (0 < calculated_size || EncodingAlgorithmFlag::PLAIN_CDR == current_encoding_)) + { + extra_size = 4; // ShortMemberHeader + + if (0x3F00 < id.id || calculated_size > std::numeric_limits::max()) + { + extra_size += 8; // LongMemberHeader + } + + } + + calculated_size += prev_size + extra_size; + if (CdrVersion::XCDRv1 != cdr_version_) + { + current_alignment += extra_size; + } + + + return calculated_size; + } + + /*! + * @brief Indicates a new constructed type will be calculated. + * @param[in] new_encoding New encoding algorithm used for the constructed type. + * @param[inout] current_alignment Current alignment in the encoding. + * @return If new encoding algorithm encodes a header, return the encoded size of it. + */ + Cdr_DllAPI size_t begin_calculate_type_serialized_size( + EncodingAlgorithmFlag new_encoding, + size_t& current_alignment); + + /*! + * @brief Indicates the ending of a constructed type. + * @param[in] new_encoding New encoding algorithm used after the constructed type. + * @param[inout] current_alignment Current alignment in the encoding. + * @return If current encoding algorithm encodes a final mark, return the encoded size of it. + */ + Cdr_DllAPI size_t end_calculate_type_serialized_size( + EncodingAlgorithmFlag new_encoding, + size_t& current_alignment); + +private: + + CdrSizeCalculator() = delete; + + CdrVersion cdr_version_ {CdrVersion::XCDRv2}; + + EncodingAlgorithmFlag current_encoding_ {EncodingAlgorithmFlag::PLAIN_CDR2}; + + enum SerializedMemberSizeForNextInt + { + NO_SERIALIZED_MEMBER_SIZE, + SERIALIZED_MEMBER_SIZE, + SERIALIZED_MEMBER_SIZE_4, + SERIALIZED_MEMBER_SIZE_8 + } + //! Specifies if a DHEADER was serialized. Used to calculate XCDRv2 member headers. + serialized_member_size_ {NO_SERIALIZED_MEMBER_SIZE}; + + //! Align for types equal or greater than 64bits. + size_t align64_ {4}; + + inline size_t alignment( + size_t current_alignment, + size_t data_size) const + { + return (data_size - (current_alignment % data_size)) & (data_size - 1); + } + + template::value || + std::is_arithmetic<_T>::value>::type* = nullptr> + constexpr SerializedMemberSizeForNextInt get_serialized_member_size() const + { + return (1 == sizeof(_T) ? SERIALIZED_MEMBER_SIZE : + (4 == sizeof(_T) ? SERIALIZED_MEMBER_SIZE_4 : + (8 == sizeof(_T) ? SERIALIZED_MEMBER_SIZE_8 : NO_SERIALIZED_MEMBER_SIZE))); + } + +}; + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FASTCDR_CDRSIZECALCULATOR_HPP_ 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..4d4e6efd775 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Accel.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 Accel.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace geometry_msgs { + +namespace msg { + + + +Accel::Accel() +{ +} + +Accel::~Accel() +{ +} + +Accel::Accel( + const Accel& x) +{ + m_linear = x.m_linear; + m_angular = x.m_angular; +} + +Accel::Accel( + Accel&& x) noexcept +{ + m_linear = std::move(x.m_linear); + m_angular = std::move(x.m_angular); +} + +Accel& Accel::operator =( + const Accel& x) +{ + + m_linear = x.m_linear; + m_angular = x.m_angular; + return *this; +} + +Accel& Accel::operator =( + Accel&& x) noexcept +{ + + m_linear = std::move(x.m_linear); + m_angular = std::move(x.m_angular); + return *this; +} + +bool Accel::operator ==( + const Accel& x) const +{ + return (m_linear == x.m_linear && + m_angular == x.m_angular); +} + +bool Accel::operator !=( + const Accel& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member linear + * @param _linear New value to be copied in member linear + */ +void 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 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& Accel::linear() const +{ + return m_linear; +} + +/*! + * @brief This function returns a reference to member linear + * @return Reference to member linear + */ +geometry_msgs::msg::Vector3& 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 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 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& Accel::angular() const +{ + return m_angular; +} + +/*! + * @brief This function returns a reference to member angular + * @return Reference to member angular + */ +geometry_msgs::msg::Vector3& Accel::angular() +{ + return m_angular; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "AccelCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Accel.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Accel.h new file mode 100644 index 00000000000..84c7a956e8f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Accel.h @@ -0,0 +1,205 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "Vector3.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(ACCEL_SOURCE) +#define ACCEL_DllAPI __declspec( dllexport ) +#else +#define ACCEL_DllAPI __declspec( dllimport ) +#endif // ACCEL_SOURCE +#else +#define ACCEL_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define ACCEL_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace geometry_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure Accel defined by the user in the IDL file. + * @ingroup Accel + */ +class Accel +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Accel(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Accel(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::Accel that will be copied. + */ + eProsima_user_DllExport Accel( + const Accel& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::Accel that will be copied. + */ + eProsima_user_DllExport Accel( + Accel&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::Accel that will be copied. + */ + eProsima_user_DllExport Accel& operator =( + const Accel& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::Accel that will be copied. + */ + eProsima_user_DllExport Accel& operator =( + Accel&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Accel object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Accel& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Accel object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Accel& 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(); + +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_ACCEL_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelCdrAux.hpp new file mode 100644 index 00000000000..aa54a1b4946 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AccelCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELCDRAUX_HPP_ + +#include "Accel.h" + +constexpr uint32_t geometry_msgs_msg_Accel_max_cdr_typesize {64UL}; +constexpr uint32_t geometry_msgs_msg_Accel_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Accel& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelCdrAux.ipp new file mode 100644 index 00000000000..fa72bc23fd2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AccelCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELCDRAUX_IPP_ + +#include "AccelCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::Accel& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.linear(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.angular(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Accel& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.linear() + << eprosima::fastcdr::MemberId(1) << data.angular() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::Accel& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.linear(); + break; + + case 1: + dcdr >> data.angular(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Accel& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELCDRAUX_IPP_ + 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..6b77938d505 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelPubSubTypes.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 AccelPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "AccelPubSubTypes.h" +#include "AccelCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + +AccelPubSubType::AccelPubSubType() +{ + setName("geometry_msgs::msg::dds_::Accel_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Accel::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_Accel_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +AccelPubSubType::~AccelPubSubType() +{ +} + +bool AccelPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool AccelPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function AccelPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..70f5984497f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Accel.h" + +#include "Vector3PubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~AccelPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCEL_PUBSUBTYPES_H_ + 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..5bc03edb0cb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariance.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 AccelWithCovariance.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace geometry_msgs { + +namespace msg { + + + +AccelWithCovariance::AccelWithCovariance() +{ +} + +AccelWithCovariance::~AccelWithCovariance() +{ +} + +AccelWithCovariance::AccelWithCovariance( + const AccelWithCovariance& x) +{ + m_accel = x.m_accel; + m_covariance = x.m_covariance; +} + +AccelWithCovariance::AccelWithCovariance( + AccelWithCovariance&& x) noexcept +{ + m_accel = std::move(x.m_accel); + m_covariance = std::move(x.m_covariance); +} + +AccelWithCovariance& AccelWithCovariance::operator =( + const AccelWithCovariance& x) +{ + + m_accel = x.m_accel; + m_covariance = x.m_covariance; + return *this; +} + +AccelWithCovariance& AccelWithCovariance::operator =( + AccelWithCovariance&& x) noexcept +{ + + m_accel = std::move(x.m_accel); + m_covariance = std::move(x.m_covariance); + return *this; +} + +bool AccelWithCovariance::operator ==( + const AccelWithCovariance& x) const +{ + return (m_accel == x.m_accel && + m_covariance == x.m_covariance); +} + +bool AccelWithCovariance::operator !=( + const AccelWithCovariance& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member accel + * @param _accel New value to be copied in member accel + */ +void 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 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& AccelWithCovariance::accel() const +{ + return m_accel; +} + +/*! + * @brief This function returns a reference to member accel + * @return Reference to member accel + */ +geometry_msgs::msg::Accel& 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 AccelWithCovariance::covariance( + const geometry_msgs::msg::double__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 AccelWithCovariance::covariance( + geometry_msgs::msg::double__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__36& AccelWithCovariance::covariance() const +{ + return m_covariance; +} + +/*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ +geometry_msgs::msg::double__36& AccelWithCovariance::covariance() +{ + return m_covariance; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "AccelWithCovarianceCdrAux.ipp" + 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..54aef9b8d77 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariance.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 AccelWithCovariance.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "Accel.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(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; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace geometry_msgs { + +namespace msg { + +typedef std::array double__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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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__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__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__36& covariance() const; + + /*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ + eProsima_user_DllExport geometry_msgs::msg::double__36& covariance(); + +private: + + geometry_msgs::msg::Accel m_accel; + geometry_msgs::msg::double__36 m_covariance{0.0}; + +}; + +} // namespace msg + +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovarianceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovarianceCdrAux.hpp new file mode 100644 index 00000000000..7fbbdf7c84e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovarianceCdrAux.hpp @@ -0,0 +1,54 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AccelWithCovarianceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCECDRAUX_HPP_ + +#include "AccelWithCovariance.h" + +constexpr uint32_t geometry_msgs_msg_AccelWithCovariance_max_cdr_typesize {360UL}; +constexpr uint32_t geometry_msgs_msg_AccelWithCovariance_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::AccelWithCovariance& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovarianceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovarianceCdrAux.ipp new file mode 100644 index 00000000000..30d59d765a6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovarianceCdrAux.ipp @@ -0,0 +1,140 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file AccelWithCovarianceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCECDRAUX_IPP_ + +#include "AccelWithCovarianceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::AccelWithCovariance& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.accel(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.covariance(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::AccelWithCovariance& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.accel() + << eprosima::fastcdr::MemberId(1) << data.covariance() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::AccelWithCovariance& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.accel(); + break; + + case 1: + dcdr >> data.covariance(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::AccelWithCovariance& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCECDRAUX_IPP_ + 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..a6b22c328ff --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariancePubSubTypes.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 AccelWithCovariancePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "AccelWithCovariancePubSubTypes.h" +#include "AccelWithCovarianceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + + + +AccelWithCovariancePubSubType::AccelWithCovariancePubSubType() +{ + setName("geometry_msgs::msg::dds_::AccelWithCovariance_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(AccelWithCovariance::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_AccelWithCovariance_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +AccelWithCovariancePubSubType::~AccelWithCovariancePubSubType() +{ +} + +bool AccelWithCovariancePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool AccelWithCovariancePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function AccelWithCovariancePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..0c51d5cc73c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/AccelWithCovariancePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "AccelWithCovariance.h" + +#include "AccelPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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__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 ~AccelWithCovariancePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_ACCELWITHCOVARIANCE_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.cxx new file mode 100644 index 00000000000..8c961c13b61 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.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 Point.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Point.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace geometry_msgs { + +namespace msg { + + + +Point::Point() +{ +} + +Point::~Point() +{ +} + +Point::Point( + const Point& x) +{ + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; +} + +Point::Point( + Point&& x) noexcept +{ + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; +} + +Point& Point::operator =( + const Point& x) +{ + + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; + return *this; +} + +Point& Point::operator =( + Point&& x) noexcept +{ + + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; + return *this; +} + +bool Point::operator ==( + const Point& x) const +{ + return (m_x == x.m_x && + m_y == x.m_y && + m_z == x.m_z); +} + +bool Point::operator !=( + const Point& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member x + * @param _x New value for member x + */ +void Point::x( + double _x) +{ + m_x = _x; +} + +/*! + * @brief This function returns the value of member x + * @return Value of member x + */ +double Point::x() const +{ + return m_x; +} + +/*! + * @brief This function returns a reference to member x + * @return Reference to member x + */ +double& Point::x() +{ + return m_x; +} + + +/*! + * @brief This function sets a value in member y + * @param _y New value for member y + */ +void Point::y( + double _y) +{ + m_y = _y; +} + +/*! + * @brief This function returns the value of member y + * @return Value of member y + */ +double Point::y() const +{ + return m_y; +} + +/*! + * @brief This function returns a reference to member y + * @return Reference to member y + */ +double& Point::y() +{ + return m_y; +} + + +/*! + * @brief This function sets a value in member z + * @param _z New value for member z + */ +void Point::z( + double _z) +{ + m_z = _z; +} + +/*! + * @brief This function returns the value of member z + * @return Value of member z + */ +double Point::z() const +{ + return m_z; +} + +/*! + * @brief This function returns a reference to member z + * @return Reference to member z + */ +double& Point::z() +{ + return m_z; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PointCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.h new file mode 100644 index 00000000000..87bb0ab2745 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point.h @@ -0,0 +1,211 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file Point.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_H_ + +#include +#include +#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(POINT_SOURCE) +#define POINT_DllAPI __declspec( dllexport ) +#else +#define POINT_DllAPI __declspec( dllimport ) +#endif // POINT_SOURCE +#else +#define POINT_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define POINT_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace geometry_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure Point defined by the user in the IDL file. + * @ingroup Point + */ +class Point +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Point(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Point(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::Point that will be copied. + */ + eProsima_user_DllExport Point( + const Point& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::Point that will be copied. + */ + eProsima_user_DllExport Point( + Point&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::Point that will be copied. + */ + eProsima_user_DllExport Point& operator =( + const Point& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::Point that will be copied. + */ + eProsima_user_DllExport Point& operator =( + Point&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Point object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Point& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Point object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Point& 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(); + +private: + + double m_x{0.0}; + double m_y{0.0}; + double m_z{0.0}; + +}; + +} // namespace msg + +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.cxx new file mode 100644 index 00000000000..e5e90485ee9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.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 Point32.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Point32.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace geometry_msgs { + +namespace msg { + + + +Point32::Point32() +{ +} + +Point32::~Point32() +{ +} + +Point32::Point32( + const Point32& x) +{ + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; +} + +Point32::Point32( + Point32&& x) noexcept +{ + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; +} + +Point32& Point32::operator =( + const Point32& x) +{ + + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; + return *this; +} + +Point32& Point32::operator =( + Point32&& x) noexcept +{ + + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; + return *this; +} + +bool Point32::operator ==( + const Point32& x) const +{ + return (m_x == x.m_x && + m_y == x.m_y && + m_z == x.m_z); +} + +bool Point32::operator !=( + const Point32& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member x + * @param _x New value for member x + */ +void Point32::x( + float _x) +{ + m_x = _x; +} + +/*! + * @brief This function returns the value of member x + * @return Value of member x + */ +float Point32::x() const +{ + return m_x; +} + +/*! + * @brief This function returns a reference to member x + * @return Reference to member x + */ +float& Point32::x() +{ + return m_x; +} + + +/*! + * @brief This function sets a value in member y + * @param _y New value for member y + */ +void Point32::y( + float _y) +{ + m_y = _y; +} + +/*! + * @brief This function returns the value of member y + * @return Value of member y + */ +float Point32::y() const +{ + return m_y; +} + +/*! + * @brief This function returns a reference to member y + * @return Reference to member y + */ +float& Point32::y() +{ + return m_y; +} + + +/*! + * @brief This function sets a value in member z + * @param _z New value for member z + */ +void Point32::z( + float _z) +{ + m_z = _z; +} + +/*! + * @brief This function returns the value of member z + * @return Value of member z + */ +float Point32::z() const +{ + return m_z; +} + +/*! + * @brief This function returns a reference to member z + * @return Reference to member z + */ +float& Point32::z() +{ + return m_z; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "Point32CdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.h new file mode 100644 index 00000000000..2032e6675c5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32.h @@ -0,0 +1,211 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file Point32.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_H_ + +#include +#include +#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(POINT32_SOURCE) +#define POINT32_DllAPI __declspec( dllexport ) +#else +#define POINT32_DllAPI __declspec( dllimport ) +#endif // POINT32_SOURCE +#else +#define POINT32_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define POINT32_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace geometry_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure Point32 defined by the user in the IDL file. + * @ingroup Point32 + */ +class Point32 +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Point32(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Point32(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::Point32 that will be copied. + */ + eProsima_user_DllExport Point32( + const Point32& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::Point32 that will be copied. + */ + eProsima_user_DllExport Point32( + Point32&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::Point32 that will be copied. + */ + eProsima_user_DllExport Point32& operator =( + const Point32& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::Point32 that will be copied. + */ + eProsima_user_DllExport Point32& operator =( + Point32&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Point32 object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Point32& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Point32 object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Point32& x) const; + + /*! + * @brief This function sets a value in member x + * @param _x New value for member x + */ + eProsima_user_DllExport void x( + float _x); + + /*! + * @brief This function returns the value of member x + * @return Value of member x + */ + eProsima_user_DllExport float x() const; + + /*! + * @brief This function returns a reference to member x + * @return Reference to member x + */ + eProsima_user_DllExport float& x(); + + + /*! + * @brief This function sets a value in member y + * @param _y New value for member y + */ + eProsima_user_DllExport void y( + float _y); + + /*! + * @brief This function returns the value of member y + * @return Value of member y + */ + eProsima_user_DllExport float y() const; + + /*! + * @brief This function returns a reference to member y + * @return Reference to member y + */ + eProsima_user_DllExport float& y(); + + + /*! + * @brief This function sets a value in member z + * @param _z New value for member z + */ + eProsima_user_DllExport void z( + float _z); + + /*! + * @brief This function returns the value of member z + * @return Value of member z + */ + eProsima_user_DllExport float z() const; + + /*! + * @brief This function returns a reference to member z + * @return Reference to member z + */ + eProsima_user_DllExport float& z(); + +private: + + float m_x{0.0}; + float m_y{0.0}; + float m_z{0.0}; + +}; + +} // namespace msg + +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32CdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32CdrAux.hpp new file mode 100644 index 00000000000..10535a4278b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32CdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file Point32CdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32CDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32CDRAUX_HPP_ + +#include "Point32.h" + +constexpr uint32_t geometry_msgs_msg_Point32_max_cdr_typesize {16UL}; +constexpr uint32_t geometry_msgs_msg_Point32_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Point32& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32CDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32CdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32CdrAux.ipp new file mode 100644 index 00000000000..888859ca3cc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32CdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file Point32CdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32CDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32CDRAUX_IPP_ + +#include "Point32CdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::Point32& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.x(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.y(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.z(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Point32& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.x() + << eprosima::fastcdr::MemberId(1) << data.y() + << eprosima::fastcdr::MemberId(2) << data.z() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::Point32& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.x(); + break; + + case 1: + dcdr >> data.y(); + break; + + case 2: + dcdr >> data.z(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Point32& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32CDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.cxx new file mode 100644 index 00000000000..7b9912c15b9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.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 Point32PubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "Point32PubSubTypes.h" +#include "Point32CdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + +Point32PubSubType::Point32PubSubType() +{ + setName("geometry_msgs::msg::dds_::Point32_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Point32::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_Point32_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +Point32PubSubType::~Point32PubSubType() +{ +} + +bool Point32PubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Point32* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool Point32PubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function Point32PubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* Point32PubSubType::createData() +{ + return reinterpret_cast(new Point32()); +} + +void Point32PubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool Point32PubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace geometry_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.h new file mode 100644 index 00000000000..6fa6e87369a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Point32PubSubTypes.h @@ -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 Point32PubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Point32.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated Point32 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 Point32 defined by the user in the IDL file. + * @ingroup Point32 + */ +class Point32PubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef Point32 type; + + eProsima_user_DllExport Point32PubSubType(); + + eProsima_user_DllExport ~Point32PubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointCdrAux.hpp new file mode 100644 index 00000000000..2e6f45415b5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PointCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINTCDRAUX_HPP_ + +#include "Point.h" + +constexpr uint32_t geometry_msgs_msg_Point_max_cdr_typesize {32UL}; +constexpr uint32_t geometry_msgs_msg_Point_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Point& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointCdrAux.ipp new file mode 100644 index 00000000000..06fef6778c5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PointCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINTCDRAUX_IPP_ + +#include "PointCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::Point& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.x(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.y(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.z(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Point& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.x() + << eprosima::fastcdr::MemberId(1) << data.y() + << eprosima::fastcdr::MemberId(2) << data.z() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::Point& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.x(); + break; + + case 1: + dcdr >> data.y(); + break; + + case 2: + dcdr >> data.z(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Point& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINTCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.cxx new file mode 100644 index 00000000000..839631831a9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.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 PointPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PointPubSubTypes.h" +#include "PointCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + +PointPubSubType::PointPubSubType() +{ + setName("geometry_msgs::msg::dds_::Point_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Point::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_Point_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PointPubSubType::~PointPubSubType() +{ +} + +bool PointPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Point* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PointPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PointPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* PointPubSubType::createData() +{ + return reinterpret_cast(new Point()); +} + +void PointPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool PointPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace geometry_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.h new file mode 100644 index 00000000000..7bd57976c26 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PointPubSubTypes.h @@ -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 PointPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Point.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated Point 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 Point defined by the user in the IDL file. + * @ingroup Point + */ +class PointPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef Point type; + + eProsima_user_DllExport PointPubSubType(); + + eProsima_user_DllExport ~PointPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_PUBSUBTYPES_H_ + 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..4cb62d86a8d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Polygon.cxx @@ -0,0 +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 Polygon.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace geometry_msgs { + +namespace msg { + + + + + +Polygon::Polygon() +{ +} + +Polygon::~Polygon() +{ +} + +Polygon::Polygon( + const Polygon& x) +{ + m_points = x.m_points; +} + +Polygon::Polygon( + Polygon&& x) noexcept +{ + m_points = std::move(x.m_points); +} + +Polygon& Polygon::operator =( + const Polygon& x) +{ + + m_points = x.m_points; + return *this; +} + +Polygon& Polygon::operator =( + Polygon&& x) noexcept +{ + + m_points = std::move(x.m_points); + return *this; +} + +bool Polygon::operator ==( + const Polygon& x) const +{ + return (m_points == x.m_points); +} + +bool Polygon::operator !=( + const Polygon& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member points + * @param _points New value to be copied in member points + */ +void 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 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& Polygon::points() const +{ + return m_points; +} + +/*! + * @brief This function returns a reference to member points + * @return Reference to member points + */ +std::vector& Polygon::points() +{ + return m_points; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PolygonCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Polygon.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Polygon.h new file mode 100644 index 00000000000..29c3149ee1d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Polygon.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "Point32.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(POLYGON_SOURCE) +#define POLYGON_DllAPI __declspec( dllexport ) +#else +#define POLYGON_DllAPI __declspec( dllimport ) +#endif // POLYGON_SOURCE +#else +#define POLYGON_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define POLYGON_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace geometry_msgs { + +namespace msg { + + + + + +/*! + * @brief This class represents the structure Polygon defined by the user in the IDL file. + * @ingroup Polygon + */ +class Polygon +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Polygon(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Polygon(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::Polygon that will be copied. + */ + eProsima_user_DllExport Polygon( + const Polygon& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::Polygon that will be copied. + */ + eProsima_user_DllExport Polygon( + Polygon&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::Polygon that will be copied. + */ + eProsima_user_DllExport Polygon& operator =( + const Polygon& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::Polygon that will be copied. + */ + eProsima_user_DllExport Polygon& operator =( + Polygon&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Polygon object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Polygon& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Polygon object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Polygon& x) const; + + /*! + * @brief This function copies the value in member points + * @param _points New value to be copied in member points + */ + eProsima_user_DllExport void points( + const std::vector& _points); + + /*! + * @brief This function moves the value in member points + * @param _points New value to be moved in member points + */ + eProsima_user_DllExport void points( + std::vector&& _points); + + /*! + * @brief This function returns a constant reference to member points + * @return Constant reference to member points + */ + eProsima_user_DllExport const std::vector& points() const; + + /*! + * @brief This function returns a reference to member points + * @return Reference to member points + */ + eProsima_user_DllExport std::vector& points(); + +private: + + std::vector m_points; + +}; + +} // namespace msg + +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonCdrAux.hpp new file mode 100644 index 00000000000..c40622add24 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PolygonCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGONCDRAUX_HPP_ + +#include "Polygon.h" + +constexpr uint32_t geometry_msgs_msg_Polygon_max_cdr_typesize {1612UL}; +constexpr uint32_t geometry_msgs_msg_Polygon_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Polygon& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonCdrAux.ipp new file mode 100644 index 00000000000..b09a70e9532 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonCdrAux.ipp @@ -0,0 +1,132 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PolygonCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGONCDRAUX_IPP_ + +#include "PolygonCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::Polygon& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.points(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Polygon& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.points() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::Polygon& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.points(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Polygon& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGONCDRAUX_IPP_ + 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..3713e481e74 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonPubSubTypes.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 PolygonPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PolygonPubSubTypes.h" +#include "PolygonCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + + + +PolygonPubSubType::PolygonPubSubType() +{ + setName("geometry_msgs::msg::dds_::Polygon_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Polygon::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_Polygon_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PolygonPubSubType::~PolygonPubSubType() +{ +} + +bool PolygonPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PolygonPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PolygonPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace geometry_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonPubSubTypes.h new file mode 100644 index 00000000000..b21c062afae --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PolygonPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Polygon.h" + +#include "Point32PubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated Polygon 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 Polygon defined by the user in the IDL file. + * @ingroup Polygon + */ +class PolygonPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef Polygon type; + + eProsima_user_DllExport PolygonPubSubType(); + + eProsima_user_DllExport ~PolygonPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POLYGON_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.cxx new file mode 100644 index 00000000000..8406befe2a3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.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 Pose.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Pose.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace geometry_msgs { + +namespace msg { + + + +Pose::Pose() +{ +} + +Pose::~Pose() +{ +} + +Pose::Pose( + const Pose& x) +{ + m_position = x.m_position; + m_orientation = x.m_orientation; +} + +Pose::Pose( + Pose&& x) noexcept +{ + m_position = std::move(x.m_position); + m_orientation = std::move(x.m_orientation); +} + +Pose& Pose::operator =( + const Pose& x) +{ + + m_position = x.m_position; + m_orientation = x.m_orientation; + return *this; +} + +Pose& Pose::operator =( + Pose&& x) noexcept +{ + + m_position = std::move(x.m_position); + m_orientation = std::move(x.m_orientation); + return *this; +} + +bool Pose::operator ==( + const Pose& x) const +{ + return (m_position == x.m_position && + m_orientation == x.m_orientation); +} + +bool Pose::operator !=( + const Pose& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member position + * @param _position New value to be copied in member position + */ +void Pose::position( + const geometry_msgs::msg::Point& _position) +{ + m_position = _position; +} + +/*! + * @brief This function moves the value in member position + * @param _position New value to be moved in member position + */ +void Pose::position( + geometry_msgs::msg::Point&& _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::Point& Pose::position() const +{ + return m_position; +} + +/*! + * @brief This function returns a reference to member position + * @return Reference to member position + */ +geometry_msgs::msg::Point& Pose::position() +{ + return m_position; +} + + +/*! + * @brief This function copies the value in member orientation + * @param _orientation New value to be copied in member orientation + */ +void Pose::orientation( + const geometry_msgs::msg::Quaternion& _orientation) +{ + m_orientation = _orientation; +} + +/*! + * @brief This function moves the value in member orientation + * @param _orientation New value to be moved in member orientation + */ +void Pose::orientation( + geometry_msgs::msg::Quaternion&& _orientation) +{ + m_orientation = std::move(_orientation); +} + +/*! + * @brief This function returns a constant reference to member orientation + * @return Constant reference to member orientation + */ +const geometry_msgs::msg::Quaternion& Pose::orientation() const +{ + return m_orientation; +} + +/*! + * @brief This function returns a reference to member orientation + * @return Reference to member orientation + */ +geometry_msgs::msg::Quaternion& Pose::orientation() +{ + return m_orientation; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PoseCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.h new file mode 100644 index 00000000000..ca22e2533b5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Pose.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file Pose.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "Quaternion.h" +#include "Point.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(POSE_SOURCE) +#define POSE_DllAPI __declspec( dllexport ) +#else +#define POSE_DllAPI __declspec( dllimport ) +#endif // POSE_SOURCE +#else +#define POSE_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define POSE_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace geometry_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure Pose defined by the user in the IDL file. + * @ingroup Pose + */ +class Pose +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Pose(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Pose(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::Pose that will be copied. + */ + eProsima_user_DllExport Pose( + const Pose& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::Pose that will be copied. + */ + eProsima_user_DllExport Pose( + Pose&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::Pose that will be copied. + */ + eProsima_user_DllExport Pose& operator =( + const Pose& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::Pose that will be copied. + */ + eProsima_user_DllExport Pose& operator =( + Pose&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Pose object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Pose& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Pose object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Pose& x) const; + + /*! + * @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::Point& _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::Point&& _position); + + /*! + * @brief This function returns a constant reference to member position + * @return Constant reference to member position + */ + eProsima_user_DllExport const geometry_msgs::msg::Point& position() const; + + /*! + * @brief This function returns a reference to member position + * @return Reference to member position + */ + eProsima_user_DllExport geometry_msgs::msg::Point& position(); + + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseCdrAux.hpp new file mode 100644 index 00000000000..f28738dfd37 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PoseCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSECDRAUX_HPP_ + +#include "Pose.h" + +constexpr uint32_t geometry_msgs_msg_Pose_max_cdr_typesize {72UL}; +constexpr uint32_t geometry_msgs_msg_Pose_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Pose& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseCdrAux.ipp new file mode 100644 index 00000000000..a33adbe12ce --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PoseCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSECDRAUX_IPP_ + +#include "PoseCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::Pose& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.position(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.orientation(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Pose& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.position() + << eprosima::fastcdr::MemberId(1) << data.orientation() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::Pose& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.position(); + break; + + case 1: + dcdr >> data.orientation(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Pose& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSECDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.cxx new file mode 100644 index 00000000000..760633e5039 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.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 PosePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PosePubSubTypes.h" +#include "PoseCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + +PosePubSubType::PosePubSubType() +{ + setName("geometry_msgs::msg::dds_::Pose_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Pose::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_Pose_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PosePubSubType::~PosePubSubType() +{ +} + +bool PosePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Pose* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PosePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PosePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* PosePubSubType::createData() +{ + return reinterpret_cast(new Pose()); +} + +void PosePubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool PosePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace geometry_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.h new file mode 100644 index 00000000000..4367dfe277c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PosePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Pose.h" + +#include "QuaternionPubSubTypes.h" +#include "PointPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + +/*! + * @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 ~PosePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.cxx new file mode 100644 index 00000000000..6f3fbcabac0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.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 PoseWithCovariance.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PoseWithCovariance.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace geometry_msgs { + +namespace msg { + + + +PoseWithCovariance::PoseWithCovariance() +{ +} + +PoseWithCovariance::~PoseWithCovariance() +{ +} + +PoseWithCovariance::PoseWithCovariance( + const PoseWithCovariance& x) +{ + m_pose = x.m_pose; + m_covariance = x.m_covariance; +} + +PoseWithCovariance::PoseWithCovariance( + PoseWithCovariance&& x) noexcept +{ + m_pose = std::move(x.m_pose); + m_covariance = std::move(x.m_covariance); +} + +PoseWithCovariance& PoseWithCovariance::operator =( + const PoseWithCovariance& x) +{ + + m_pose = x.m_pose; + m_covariance = x.m_covariance; + return *this; +} + +PoseWithCovariance& PoseWithCovariance::operator =( + PoseWithCovariance&& x) noexcept +{ + + m_pose = std::move(x.m_pose); + m_covariance = std::move(x.m_covariance); + return *this; +} + +bool PoseWithCovariance::operator ==( + const PoseWithCovariance& x) const +{ + return (m_pose == x.m_pose && + m_covariance == x.m_covariance); +} + +bool PoseWithCovariance::operator !=( + const PoseWithCovariance& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member pose + * @param _pose New value to be copied in member pose + */ +void PoseWithCovariance::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 PoseWithCovariance::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& PoseWithCovariance::pose() const +{ + return m_pose; +} + +/*! + * @brief This function returns a reference to member pose + * @return Reference to member pose + */ +geometry_msgs::msg::Pose& PoseWithCovariance::pose() +{ + return m_pose; +} + + +/*! + * @brief This function copies the value in member covariance + * @param _covariance New value to be copied in member covariance + */ +void PoseWithCovariance::covariance( + const geometry_msgs::msg::double__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 PoseWithCovariance::covariance( + geometry_msgs::msg::double__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__36& PoseWithCovariance::covariance() const +{ + return m_covariance; +} + +/*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ +geometry_msgs::msg::double__36& PoseWithCovariance::covariance() +{ + return m_covariance; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PoseWithCovarianceCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.h new file mode 100644 index 00000000000..d2c65faa433 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariance.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 PoseWithCovariance.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "Pose.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(POSEWITHCOVARIANCE_SOURCE) +#define POSEWITHCOVARIANCE_DllAPI __declspec( dllexport ) +#else +#define POSEWITHCOVARIANCE_DllAPI __declspec( dllimport ) +#endif // POSEWITHCOVARIANCE_SOURCE +#else +#define POSEWITHCOVARIANCE_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define POSEWITHCOVARIANCE_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace geometry_msgs { + +namespace msg { + +typedef std::array double__36; + + + +/*! + * @brief This class represents the structure PoseWithCovariance defined by the user in the IDL file. + * @ingroup PoseWithCovariance + */ +class PoseWithCovariance +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PoseWithCovariance(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PoseWithCovariance(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::PoseWithCovariance that will be copied. + */ + eProsima_user_DllExport PoseWithCovariance( + const PoseWithCovariance& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::PoseWithCovariance that will be copied. + */ + eProsima_user_DllExport PoseWithCovariance( + PoseWithCovariance&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::PoseWithCovariance that will be copied. + */ + eProsima_user_DllExport PoseWithCovariance& operator =( + const PoseWithCovariance& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::PoseWithCovariance that will be copied. + */ + eProsima_user_DllExport PoseWithCovariance& operator =( + PoseWithCovariance&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::PoseWithCovariance object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PoseWithCovariance& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::PoseWithCovariance object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PoseWithCovariance& x) const; + + /*! + * @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 covariance + * @param _covariance New value to be copied in member covariance + */ + eProsima_user_DllExport void covariance( + const geometry_msgs::msg::double__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__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__36& covariance() const; + + /*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ + eProsima_user_DllExport geometry_msgs::msg::double__36& covariance(); + +private: + + geometry_msgs::msg::Pose m_pose; + geometry_msgs::msg::double__36 m_covariance{0.0}; + +}; + +} // namespace msg + +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovarianceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovarianceCdrAux.hpp new file mode 100644 index 00000000000..b610c1d96d9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovarianceCdrAux.hpp @@ -0,0 +1,53 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PoseWithCovarianceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCECDRAUX_HPP_ + +#include "PoseWithCovariance.h" + +constexpr uint32_t geometry_msgs_msg_PoseWithCovariance_max_cdr_typesize {368UL}; +constexpr uint32_t geometry_msgs_msg_PoseWithCovariance_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::PoseWithCovariance& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovarianceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovarianceCdrAux.ipp new file mode 100644 index 00000000000..7cbafe07cd5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovarianceCdrAux.ipp @@ -0,0 +1,140 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PoseWithCovarianceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCECDRAUX_IPP_ + +#include "PoseWithCovarianceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::PoseWithCovariance& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.pose(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.covariance(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::PoseWithCovariance& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.pose() + << eprosima::fastcdr::MemberId(1) << data.covariance() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::PoseWithCovariance& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.pose(); + break; + + case 1: + dcdr >> data.covariance(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::PoseWithCovariance& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCECDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariancePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariancePubSubTypes.cxx new file mode 100644 index 00000000000..fb964e35768 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariancePubSubTypes.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 PoseWithCovariancePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PoseWithCovariancePubSubTypes.h" +#include "PoseWithCovarianceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + + + +PoseWithCovariancePubSubType::PoseWithCovariancePubSubType() +{ + setName("geometry_msgs::msg::dds_::PoseWithCovariance_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PoseWithCovariance::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_PoseWithCovariance_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PoseWithCovariancePubSubType::~PoseWithCovariancePubSubType() +{ +} + +bool PoseWithCovariancePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + PoseWithCovariance* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PoseWithCovariancePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PoseWithCovariancePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* PoseWithCovariancePubSubType::createData() +{ + return reinterpret_cast(new PoseWithCovariance()); +} + +void PoseWithCovariancePubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool PoseWithCovariancePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..ca88a0fc7f3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/PoseWithCovariancePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "PoseWithCovariance.h" + +#include "PosePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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__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 ~PoseWithCovariancePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Quaternion.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Quaternion.cxx new file mode 100644 index 00000000000..c8af7051f43 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Quaternion.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 Quaternion.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Quaternion.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace geometry_msgs { + +namespace msg { + + + +Quaternion::Quaternion() +{ +} + +Quaternion::~Quaternion() +{ +} + +Quaternion::Quaternion( + const Quaternion& x) +{ + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; + m_w = x.m_w; +} + +Quaternion::Quaternion( + Quaternion&& x) noexcept +{ + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; + m_w = x.m_w; +} + +Quaternion& Quaternion::operator =( + const Quaternion& x) +{ + + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; + m_w = x.m_w; + return *this; +} + +Quaternion& Quaternion::operator =( + Quaternion&& x) noexcept +{ + + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; + m_w = x.m_w; + return *this; +} + +bool 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); +} + +bool Quaternion::operator !=( + const Quaternion& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member x + * @param _x New value for member x + */ +void Quaternion::x( + double _x) +{ + m_x = _x; +} + +/*! + * @brief This function returns the value of member x + * @return Value of member x + */ +double Quaternion::x() const +{ + return m_x; +} + +/*! + * @brief This function returns a reference to member x + * @return Reference to member x + */ +double& Quaternion::x() +{ + return m_x; +} + + +/*! + * @brief This function sets a value in member y + * @param _y New value for member y + */ +void Quaternion::y( + double _y) +{ + m_y = _y; +} + +/*! + * @brief This function returns the value of member y + * @return Value of member y + */ +double Quaternion::y() const +{ + return m_y; +} + +/*! + * @brief This function returns a reference to member y + * @return Reference to member y + */ +double& Quaternion::y() +{ + return m_y; +} + + +/*! + * @brief This function sets a value in member z + * @param _z New value for member z + */ +void Quaternion::z( + double _z) +{ + m_z = _z; +} + +/*! + * @brief This function returns the value of member z + * @return Value of member z + */ +double Quaternion::z() const +{ + return m_z; +} + +/*! + * @brief This function returns a reference to member z + * @return Reference to member z + */ +double& Quaternion::z() +{ + return m_z; +} + + +/*! + * @brief This function sets a value in member w + * @param _w New value for member w + */ +void Quaternion::w( + double _w) +{ + m_w = _w; +} + +/*! + * @brief This function returns the value of member w + * @return Value of member w + */ +double Quaternion::w() const +{ + return m_w; +} + +/*! + * @brief This function returns a reference to member w + * @return Reference to member w + */ +double& Quaternion::w() +{ + return m_w; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "QuaternionCdrAux.ipp" + 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..9692f430aee --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Quaternion.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 Quaternion.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 +#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; +class CdrSizeCalculator; +} // 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(); + +private: + + double m_x{0.0}; + double m_y{0.0}; + double m_z{0.0}; + double m_w{1.0}; + +}; + +} // namespace msg + +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionCdrAux.hpp new file mode 100644 index 00000000000..1284f107077 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file QuaternionCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNIONCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNIONCDRAUX_HPP_ + +#include "Quaternion.h" + +constexpr uint32_t geometry_msgs_msg_Quaternion_max_cdr_typesize {40UL}; +constexpr uint32_t geometry_msgs_msg_Quaternion_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Quaternion& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNIONCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionCdrAux.ipp new file mode 100644 index 00000000000..908fc8f3ae4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionCdrAux.ipp @@ -0,0 +1,154 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file QuaternionCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNIONCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNIONCDRAUX_IPP_ + +#include "QuaternionCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::Quaternion& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.x(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.y(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.z(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.w(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Quaternion& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.x() + << eprosima::fastcdr::MemberId(1) << data.y() + << eprosima::fastcdr::MemberId(2) << data.z() + << eprosima::fastcdr::MemberId(3) << data.w() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::Quaternion& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.x(); + break; + + case 1: + dcdr >> data.y(); + break; + + case 2: + dcdr >> data.z(); + break; + + case 3: + dcdr >> data.w(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Quaternion& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNIONCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.cxx new file mode 100644 index 00000000000..6b4163c8702 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.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 QuaternionPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "QuaternionPubSubTypes.h" +#include "QuaternionCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + +QuaternionPubSubType::QuaternionPubSubType() +{ + setName("geometry_msgs::msg::dds_::Quaternion_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Quaternion::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_Quaternion_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +QuaternionPubSubType::~QuaternionPubSubType() +{ +} + +bool QuaternionPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Quaternion* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool QuaternionPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function QuaternionPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* QuaternionPubSubType::createData() +{ + return reinterpret_cast(new Quaternion()); +} + +void QuaternionPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool QuaternionPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace geometry_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.h new file mode 100644 index 00000000000..8a9def53d95 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/QuaternionPubSubTypes.h @@ -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 QuaternionPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Quaternion.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated Quaternion 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 Quaternion defined by the user in the IDL file. + * @ingroup Quaternion + */ +class QuaternionPubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef Quaternion type; + + eProsima_user_DllExport QuaternionPubSubType(); + + eProsima_user_DllExport ~QuaternionPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Transform.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Transform.cxx new file mode 100644 index 00000000000..1b6238f7136 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Transform.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 Transform.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Transform.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace geometry_msgs { + +namespace msg { + + + +Transform::Transform() +{ +} + +Transform::~Transform() +{ +} + +Transform::Transform( + const Transform& x) +{ + m_translation = x.m_translation; + m_rotation = x.m_rotation; +} + +Transform::Transform( + Transform&& x) noexcept +{ + m_translation = std::move(x.m_translation); + m_rotation = std::move(x.m_rotation); +} + +Transform& Transform::operator =( + const Transform& x) +{ + + m_translation = x.m_translation; + m_rotation = x.m_rotation; + return *this; +} + +Transform& Transform::operator =( + Transform&& x) noexcept +{ + + m_translation = std::move(x.m_translation); + m_rotation = std::move(x.m_rotation); + return *this; +} + +bool Transform::operator ==( + const Transform& x) const +{ + return (m_translation == x.m_translation && + m_rotation == x.m_rotation); +} + +bool Transform::operator !=( + const Transform& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member translation + * @param _translation New value to be copied in member translation + */ +void Transform::translation( + const geometry_msgs::msg::Vector3& _translation) +{ + m_translation = _translation; +} + +/*! + * @brief This function moves the value in member translation + * @param _translation New value to be moved in member translation + */ +void Transform::translation( + geometry_msgs::msg::Vector3&& _translation) +{ + m_translation = std::move(_translation); +} + +/*! + * @brief This function returns a constant reference to member translation + * @return Constant reference to member translation + */ +const geometry_msgs::msg::Vector3& Transform::translation() const +{ + return m_translation; +} + +/*! + * @brief This function returns a reference to member translation + * @return Reference to member translation + */ +geometry_msgs::msg::Vector3& Transform::translation() +{ + return m_translation; +} + + +/*! + * @brief This function copies the value in member rotation + * @param _rotation New value to be copied in member rotation + */ +void Transform::rotation( + const geometry_msgs::msg::Quaternion& _rotation) +{ + m_rotation = _rotation; +} + +/*! + * @brief This function moves the value in member rotation + * @param _rotation New value to be moved in member rotation + */ +void Transform::rotation( + geometry_msgs::msg::Quaternion&& _rotation) +{ + m_rotation = std::move(_rotation); +} + +/*! + * @brief This function returns a constant reference to member rotation + * @return Constant reference to member rotation + */ +const geometry_msgs::msg::Quaternion& Transform::rotation() const +{ + return m_rotation; +} + +/*! + * @brief This function returns a reference to member rotation + * @return Reference to member rotation + */ +geometry_msgs::msg::Quaternion& Transform::rotation() +{ + return m_rotation; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "TransformCdrAux.ipp" + 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..542c0b33bc4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Transform.h @@ -0,0 +1,206 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "Quaternion.h" +#include "Vector3.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(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; +class CdrSizeCalculator; +} // 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(); + +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/fastdds/geometry_msgs/msg/TransformCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformCdrAux.hpp new file mode 100644 index 00000000000..b05278fca64 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformCdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TransformCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMCDRAUX_HPP_ + +#include "Transform.h" + +constexpr uint32_t geometry_msgs_msg_Transform_max_cdr_typesize {72UL}; +constexpr uint32_t geometry_msgs_msg_Transform_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Transform& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformCdrAux.ipp new file mode 100644 index 00000000000..2efb7ce1140 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TransformCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMCDRAUX_IPP_ + +#include "TransformCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::Transform& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.translation(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.rotation(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Transform& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.translation() + << eprosima::fastcdr::MemberId(1) << data.rotation() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::Transform& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.translation(); + break; + + case 1: + dcdr >> data.rotation(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Transform& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformPubSubTypes.cxx new file mode 100644 index 00000000000..2cf35c3f936 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformPubSubTypes.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 TransformPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "TransformPubSubTypes.h" +#include "TransformCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + +TransformPubSubType::TransformPubSubType() +{ + setName("geometry_msgs::msg::dds_::Transform_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Transform::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_Transform_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +TransformPubSubType::~TransformPubSubType() +{ +} + +bool TransformPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Transform* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool TransformPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + Transform* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function TransformPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* TransformPubSubType::createData() +{ + return reinterpret_cast(new Transform()); +} + +void TransformPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool TransformPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace geometry_msgs + 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..bb13e517dc1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Transform.h" + +#include "QuaternionPubSubTypes.h" +#include "Vector3PubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + +/*! + * @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 ~TransformPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORM_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStamped.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStamped.cxx new file mode 100644 index 00000000000..5b3fc3016e2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStamped.cxx @@ -0,0 +1,229 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "TransformStamped.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace geometry_msgs { + +namespace msg { + + + +TransformStamped::TransformStamped() +{ +} + +TransformStamped::~TransformStamped() +{ +} + +TransformStamped::TransformStamped( + const TransformStamped& x) +{ + m_header = x.m_header; + m_child_frame_id = x.m_child_frame_id; + m_transform = x.m_transform; +} + +TransformStamped::TransformStamped( + TransformStamped&& x) noexcept +{ + m_header = std::move(x.m_header); + m_child_frame_id = std::move(x.m_child_frame_id); + m_transform = std::move(x.m_transform); +} + +TransformStamped& TransformStamped::operator =( + const TransformStamped& x) +{ + + m_header = x.m_header; + m_child_frame_id = x.m_child_frame_id; + m_transform = x.m_transform; + return *this; +} + +TransformStamped& TransformStamped::operator =( + TransformStamped&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_child_frame_id = std::move(x.m_child_frame_id); + m_transform = std::move(x.m_transform); + return *this; +} + +bool TransformStamped::operator ==( + const TransformStamped& x) const +{ + return (m_header == x.m_header && + m_child_frame_id == x.m_child_frame_id && + m_transform == x.m_transform); +} + +bool TransformStamped::operator !=( + const TransformStamped& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void TransformStamped::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 TransformStamped::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& TransformStamped::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& TransformStamped::header() +{ + return m_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 + */ +void TransformStamped::child_frame_id( + const std::string& _child_frame_id) +{ + m_child_frame_id = _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 + */ +void TransformStamped::child_frame_id( + std::string&& _child_frame_id) +{ + m_child_frame_id = std::move(_child_frame_id); +} + +/*! + * @brief This function returns a constant reference to member child_frame_id + * @return Constant reference to member child_frame_id + */ +const std::string& TransformStamped::child_frame_id() const +{ + return m_child_frame_id; +} + +/*! + * @brief This function returns a reference to member child_frame_id + * @return Reference to member child_frame_id + */ +std::string& TransformStamped::child_frame_id() +{ + return m_child_frame_id; +} + + +/*! + * @brief This function copies the value in member transform + * @param _transform New value to be copied in member transform + */ +void TransformStamped::transform( + const geometry_msgs::msg::Transform& _transform) +{ + m_transform = _transform; +} + +/*! + * @brief This function moves the value in member transform + * @param _transform New value to be moved in member transform + */ +void TransformStamped::transform( + geometry_msgs::msg::Transform&& _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::Transform& TransformStamped::transform() const +{ + return m_transform; +} + +/*! + * @brief This function returns a reference to member transform + * @return Reference to member transform + */ +geometry_msgs::msg::Transform& TransformStamped::transform() +{ + return m_transform; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "TransformStampedCdrAux.ipp" + 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..fad7d457f9f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStamped.h @@ -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 TransformStamped.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "std_msgs/msg/Header.h" +#include "Transform.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(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; +class CdrSizeCalculator; +} // 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(); + +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/fastdds/geometry_msgs/msg/TransformStampedCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedCdrAux.hpp new file mode 100644 index 00000000000..3fb5ad36aff --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TransformStampedCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPEDCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPEDCDRAUX_HPP_ + +#include "TransformStamped.h" + +constexpr uint32_t geometry_msgs_msg_TransformStamped_max_cdr_typesize {616UL}; +constexpr uint32_t geometry_msgs_msg_TransformStamped_max_key_cdr_typesize {0UL}; + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::TransformStamped& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPEDCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedCdrAux.ipp new file mode 100644 index 00000000000..c7a7f566d1f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedCdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TransformStampedCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPEDCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPEDCDRAUX_IPP_ + +#include "TransformStampedCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::TransformStamped& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.child_frame_id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.transform(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::TransformStamped& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.child_frame_id() + << eprosima::fastcdr::MemberId(2) << data.transform() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::TransformStamped& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.child_frame_id(); + break; + + case 2: + dcdr >> data.transform(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::TransformStamped& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPEDCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedPubSubTypes.cxx new file mode 100644 index 00000000000..c0ecfc64fdb --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedPubSubTypes.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 TransformStampedPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "TransformStampedPubSubTypes.h" +#include "TransformStampedCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + +TransformStampedPubSubType::TransformStampedPubSubType() +{ + setName("geometry_msgs::msg::dds_::TransformStamped_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(TransformStamped::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_TransformStamped_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +TransformStampedPubSubType::~TransformStampedPubSubType() +{ +} + +bool TransformStampedPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + TransformStamped* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool TransformStampedPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + TransformStamped* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function TransformStampedPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* TransformStampedPubSubType::createData() +{ + return reinterpret_cast(new TransformStamped()); +} + +void TransformStampedPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool TransformStampedPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace geometry_msgs + 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..84ef84deb16 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TransformStampedPubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "TransformStamped.h" + +#include "std_msgs/msg/HeaderPubSubTypes.h" +#include "TransformPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~TransformStampedPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TRANSFORMSTAMPED_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Twist.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Twist.cxx new file mode 100644 index 00000000000..500234acc6e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Twist.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 Twist.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Twist.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace geometry_msgs { + +namespace msg { + + + +Twist::Twist() +{ +} + +Twist::~Twist() +{ +} + +Twist::Twist( + const Twist& x) +{ + m_linear = x.m_linear; + m_angular = x.m_angular; +} + +Twist::Twist( + Twist&& x) noexcept +{ + m_linear = std::move(x.m_linear); + m_angular = std::move(x.m_angular); +} + +Twist& Twist::operator =( + const Twist& x) +{ + + m_linear = x.m_linear; + m_angular = x.m_angular; + return *this; +} + +Twist& Twist::operator =( + Twist&& x) noexcept +{ + + m_linear = std::move(x.m_linear); + m_angular = std::move(x.m_angular); + return *this; +} + +bool Twist::operator ==( + const Twist& x) const +{ + return (m_linear == x.m_linear && + m_angular == x.m_angular); +} + +bool Twist::operator !=( + const Twist& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member linear + * @param _linear New value to be copied in member linear + */ +void Twist::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 Twist::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& Twist::linear() const +{ + return m_linear; +} + +/*! + * @brief This function returns a reference to member linear + * @return Reference to member linear + */ +geometry_msgs::msg::Vector3& Twist::linear() +{ + return m_linear; +} + + +/*! + * @brief This function copies the value in member angular + * @param _angular New value to be copied in member angular + */ +void Twist::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 Twist::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& Twist::angular() const +{ + return m_angular; +} + +/*! + * @brief This function returns a reference to member angular + * @return Reference to member angular + */ +geometry_msgs::msg::Vector3& Twist::angular() +{ + return m_angular; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "TwistCdrAux.ipp" + 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..e197806f04f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Twist.h @@ -0,0 +1,205 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "Vector3.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(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; +class CdrSizeCalculator; +} // 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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistCdrAux.hpp new file mode 100644 index 00000000000..e431d85bd5e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TwistCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTCDRAUX_HPP_ + +#include "Twist.h" + +constexpr uint32_t geometry_msgs_msg_Twist_max_cdr_typesize {64UL}; +constexpr uint32_t geometry_msgs_msg_Twist_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Twist& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistCdrAux.ipp new file mode 100644 index 00000000000..c3d9511216a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TwistCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTCDRAUX_IPP_ + +#include "TwistCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::Twist& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.linear(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.angular(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Twist& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.linear() + << eprosima::fastcdr::MemberId(1) << data.angular() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::Twist& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.linear(); + break; + + case 1: + dcdr >> data.angular(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Twist& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistPubSubTypes.cxx new file mode 100644 index 00000000000..97feada28d0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistPubSubTypes.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 TwistPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "TwistPubSubTypes.h" +#include "TwistCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + +TwistPubSubType::TwistPubSubType() +{ + setName("geometry_msgs::msg::dds_::Twist_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Twist::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_Twist_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +TwistPubSubType::~TwistPubSubType() +{ +} + +bool TwistPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Twist* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool TwistPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function TwistPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* TwistPubSubType::createData() +{ + return reinterpret_cast(new Twist()); +} + +void TwistPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool TwistPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..caf2cf08f85 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Twist.h" + +#include "Vector3PubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~TwistPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWIST_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.cxx new file mode 100644 index 00000000000..fa4fd569422 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.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 TwistWithCovariance.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "TwistWithCovariance.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace geometry_msgs { + +namespace msg { + + + +TwistWithCovariance::TwistWithCovariance() +{ +} + +TwistWithCovariance::~TwistWithCovariance() +{ +} + +TwistWithCovariance::TwistWithCovariance( + const TwistWithCovariance& x) +{ + m_twist = x.m_twist; + m_covariance = x.m_covariance; +} + +TwistWithCovariance::TwistWithCovariance( + TwistWithCovariance&& x) noexcept +{ + m_twist = std::move(x.m_twist); + m_covariance = std::move(x.m_covariance); +} + +TwistWithCovariance& TwistWithCovariance::operator =( + const TwistWithCovariance& x) +{ + + m_twist = x.m_twist; + m_covariance = x.m_covariance; + return *this; +} + +TwistWithCovariance& TwistWithCovariance::operator =( + TwistWithCovariance&& x) noexcept +{ + + m_twist = std::move(x.m_twist); + m_covariance = std::move(x.m_covariance); + return *this; +} + +bool TwistWithCovariance::operator ==( + const TwistWithCovariance& x) const +{ + return (m_twist == x.m_twist && + m_covariance == x.m_covariance); +} + +bool TwistWithCovariance::operator !=( + const TwistWithCovariance& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member twist + * @param _twist New value to be copied in member twist + */ +void TwistWithCovariance::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 TwistWithCovariance::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& TwistWithCovariance::twist() const +{ + return m_twist; +} + +/*! + * @brief This function returns a reference to member twist + * @return Reference to member twist + */ +geometry_msgs::msg::Twist& 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 TwistWithCovariance::covariance( + const geometry_msgs::msg::double__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 TwistWithCovariance::covariance( + geometry_msgs::msg::double__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__36& TwistWithCovariance::covariance() const +{ + return m_covariance; +} + +/*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ +geometry_msgs::msg::double__36& TwistWithCovariance::covariance() +{ + return m_covariance; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "TwistWithCovarianceCdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.h new file mode 100644 index 00000000000..ae1a23b7686 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariance.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 TwistWithCovariance.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "Twist.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(TWISTWITHCOVARIANCE_SOURCE) +#define TWISTWITHCOVARIANCE_DllAPI __declspec( dllexport ) +#else +#define TWISTWITHCOVARIANCE_DllAPI __declspec( dllimport ) +#endif // TWISTWITHCOVARIANCE_SOURCE +#else +#define TWISTWITHCOVARIANCE_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define TWISTWITHCOVARIANCE_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace geometry_msgs { + +namespace msg { + +typedef std::array double__36; + + + +/*! + * @brief This class represents the structure TwistWithCovariance defined by the user in the IDL file. + * @ingroup TwistWithCovariance + */ +class TwistWithCovariance +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport TwistWithCovariance(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~TwistWithCovariance(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::TwistWithCovariance that will be copied. + */ + eProsima_user_DllExport TwistWithCovariance( + const TwistWithCovariance& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::TwistWithCovariance that will be copied. + */ + eProsima_user_DllExport TwistWithCovariance( + TwistWithCovariance&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::TwistWithCovariance that will be copied. + */ + eProsima_user_DllExport TwistWithCovariance& operator =( + const TwistWithCovariance& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::TwistWithCovariance that will be copied. + */ + eProsima_user_DllExport TwistWithCovariance& operator =( + TwistWithCovariance&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::TwistWithCovariance object to compare. + */ + eProsima_user_DllExport bool operator ==( + const TwistWithCovariance& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::TwistWithCovariance object to compare. + */ + eProsima_user_DllExport bool operator !=( + const TwistWithCovariance& x) const; + + /*! + * @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 covariance + * @param _covariance New value to be copied in member covariance + */ + eProsima_user_DllExport void covariance( + const geometry_msgs::msg::double__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__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__36& covariance() const; + + /*! + * @brief This function returns a reference to member covariance + * @return Reference to member covariance + */ + eProsima_user_DllExport geometry_msgs::msg::double__36& covariance(); + +private: + + geometry_msgs::msg::Twist m_twist; + geometry_msgs::msg::double__36 m_covariance{0.0}; + +}; + +} // namespace msg + +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovarianceCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovarianceCdrAux.hpp new file mode 100644 index 00000000000..4b812f1d11a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovarianceCdrAux.hpp @@ -0,0 +1,55 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TwistWithCovarianceCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCECDRAUX_HPP_ + +#include "TwistWithCovariance.h" + +constexpr uint32_t geometry_msgs_msg_TwistWithCovariance_max_cdr_typesize {360UL}; +constexpr uint32_t geometry_msgs_msg_TwistWithCovariance_max_key_cdr_typesize {0UL}; + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::TwistWithCovariance& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovarianceCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovarianceCdrAux.ipp new file mode 100644 index 00000000000..a53a1c15986 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovarianceCdrAux.ipp @@ -0,0 +1,140 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TwistWithCovarianceCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCECDRAUX_IPP_ + +#include "TwistWithCovarianceCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::TwistWithCovariance& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.twist(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.covariance(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::TwistWithCovariance& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.twist() + << eprosima::fastcdr::MemberId(1) << data.covariance() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::TwistWithCovariance& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.twist(); + break; + + case 1: + dcdr >> data.covariance(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::TwistWithCovariance& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCECDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariancePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariancePubSubTypes.cxx new file mode 100644 index 00000000000..93f8830bb86 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariancePubSubTypes.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 TwistWithCovariancePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "TwistWithCovariancePubSubTypes.h" +#include "TwistWithCovarianceCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + + + +TwistWithCovariancePubSubType::TwistWithCovariancePubSubType() +{ + setName("geometry_msgs::msg::dds_::TwistWithCovariance_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(TwistWithCovariance::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_TwistWithCovariance_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +TwistWithCovariancePubSubType::~TwistWithCovariancePubSubType() +{ +} + +bool TwistWithCovariancePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + TwistWithCovariance* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool TwistWithCovariancePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function TwistWithCovariancePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* TwistWithCovariancePubSubType::createData() +{ + return reinterpret_cast(new TwistWithCovariance()); +} + +void TwistWithCovariancePubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool TwistWithCovariancePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..c229f83da7e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/TwistWithCovariancePubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "TwistWithCovariance.h" + +#include "TwistPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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__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 ~TwistWithCovariancePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.cxx new file mode 100644 index 00000000000..e347e156167 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.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 Vector3.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Vector3.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace geometry_msgs { + +namespace msg { + + + +Vector3::Vector3() +{ +} + +Vector3::~Vector3() +{ +} + +Vector3::Vector3( + const Vector3& x) +{ + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; +} + +Vector3::Vector3( + Vector3&& x) noexcept +{ + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; +} + +Vector3& Vector3::operator =( + const Vector3& x) +{ + + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; + return *this; +} + +Vector3& Vector3::operator =( + Vector3&& x) noexcept +{ + + m_x = x.m_x; + m_y = x.m_y; + m_z = x.m_z; + return *this; +} + +bool Vector3::operator ==( + const Vector3& x) const +{ + return (m_x == x.m_x && + m_y == x.m_y && + m_z == x.m_z); +} + +bool Vector3::operator !=( + const Vector3& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member x + * @param _x New value for member x + */ +void Vector3::x( + double _x) +{ + m_x = _x; +} + +/*! + * @brief This function returns the value of member x + * @return Value of member x + */ +double Vector3::x() const +{ + return m_x; +} + +/*! + * @brief This function returns a reference to member x + * @return Reference to member x + */ +double& Vector3::x() +{ + return m_x; +} + + +/*! + * @brief This function sets a value in member y + * @param _y New value for member y + */ +void Vector3::y( + double _y) +{ + m_y = _y; +} + +/*! + * @brief This function returns the value of member y + * @return Value of member y + */ +double Vector3::y() const +{ + return m_y; +} + +/*! + * @brief This function returns a reference to member y + * @return Reference to member y + */ +double& Vector3::y() +{ + return m_y; +} + + +/*! + * @brief This function sets a value in member z + * @param _z New value for member z + */ +void Vector3::z( + double _z) +{ + m_z = _z; +} + +/*! + * @brief This function returns the value of member z + * @return Value of member z + */ +double Vector3::z() const +{ + return m_z; +} + +/*! + * @brief This function returns a reference to member z + * @return Reference to member z + */ +double& Vector3::z() +{ + return m_z; +} + + + + +} // namespace msg + + +} // namespace geometry_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "Vector3CdrAux.ipp" + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.h new file mode 100644 index 00000000000..69b5eea4724 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3.h @@ -0,0 +1,211 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file Vector3.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_H_ + +#include +#include +#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(VECTOR3_SOURCE) +#define VECTOR3_DllAPI __declspec( dllexport ) +#else +#define VECTOR3_DllAPI __declspec( dllimport ) +#endif // VECTOR3_SOURCE +#else +#define VECTOR3_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define VECTOR3_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace geometry_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure Vector3 defined by the user in the IDL file. + * @ingroup Vector3 + */ +class Vector3 +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport Vector3(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~Vector3(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object geometry_msgs::msg::Vector3 that will be copied. + */ + eProsima_user_DllExport Vector3( + const Vector3& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object geometry_msgs::msg::Vector3 that will be copied. + */ + eProsima_user_DllExport Vector3( + Vector3&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object geometry_msgs::msg::Vector3 that will be copied. + */ + eProsima_user_DllExport Vector3& operator =( + const Vector3& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object geometry_msgs::msg::Vector3 that will be copied. + */ + eProsima_user_DllExport Vector3& operator =( + Vector3&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Vector3 object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Vector3& x) const; + + /*! + * @brief Comparison operator. + * @param x geometry_msgs::msg::Vector3 object to compare. + */ + eProsima_user_DllExport bool operator !=( + const Vector3& 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(); + +private: + + double m_x{0.0}; + double m_y{0.0}; + double m_z{0.0}; + +}; + +} // namespace msg + +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3CdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3CdrAux.hpp new file mode 100644 index 00000000000..b64061fdc57 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3CdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file Vector3CdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3CDRAUX_HPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3CDRAUX_HPP_ + +#include "Vector3.h" + +constexpr uint32_t geometry_msgs_msg_Vector3_max_cdr_typesize {32UL}; +constexpr uint32_t geometry_msgs_msg_Vector3_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Vector3& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3CDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3CdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3CdrAux.ipp new file mode 100644 index 00000000000..a565fb67f0c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3CdrAux.ipp @@ -0,0 +1,146 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file Vector3CdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3CDRAUX_IPP_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3CDRAUX_IPP_ + +#include "Vector3CdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const geometry_msgs::msg::Vector3& data, + size_t& current_alignment) +{ + using namespace geometry_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.x(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.y(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.z(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Vector3& data) +{ + using namespace geometry_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.x() + << eprosima::fastcdr::MemberId(1) << data.y() + << eprosima::fastcdr::MemberId(2) << data.z() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + geometry_msgs::msg::Vector3& data) +{ + using namespace geometry_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.x(); + break; + + case 1: + dcdr >> data.y(); + break; + + case 2: + dcdr >> data.z(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const geometry_msgs::msg::Vector3& data) +{ + using namespace geometry_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3CDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.cxx new file mode 100644 index 00000000000..c6ebe531854 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.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 Vector3PubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "Vector3PubSubTypes.h" +#include "Vector3CdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace geometry_msgs { +namespace msg { + + +Vector3PubSubType::Vector3PubSubType() +{ + setName("geometry_msgs::msg::dds_::Vector3_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Vector3::getMaxCdrSerializedSize()); +#else + geometry_msgs_msg_Vector3_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +Vector3PubSubType::~Vector3PubSubType() +{ +} + +bool Vector3PubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Vector3* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool Vector3PubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 deserializes the data. + eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function Vector3PubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* Vector3PubSubType::createData() +{ + return reinterpret_cast(new Vector3()); +} + +void Vector3PubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool Vector3PubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace geometry_msgs + diff --git a/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.h b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.h new file mode 100644 index 00000000000..e883ac1f3ca --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/geometry_msgs/msg/Vector3PubSubTypes.h @@ -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 Vector3PubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Vector3.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated Vector3 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 Vector3 defined by the user in the IDL file. + * @ingroup Vector3 + */ +class Vector3PubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef Vector3 type; + + eProsima_user_DllExport Vector3PubSubType(); + + eProsima_user_DllExport ~Vector3PubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace geometry_msgs + +#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/Odometry.cxx b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/Odometry.cxx new file mode 100644 index 00000000000..dc54b84b213 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/Odometry.cxx @@ -0,0 +1,273 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Odometry.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace nav_msgs { + +namespace msg { + + + +Odometry::Odometry() +{ +} + +Odometry::~Odometry() +{ +} + +Odometry::Odometry( + const Odometry& x) +{ + m_header = x.m_header; + m_child_frame_id = x.m_child_frame_id; + m_pose = x.m_pose; + m_twist = x.m_twist; +} + +Odometry::Odometry( + Odometry&& x) noexcept +{ + m_header = std::move(x.m_header); + m_child_frame_id = std::move(x.m_child_frame_id); + m_pose = std::move(x.m_pose); + m_twist = std::move(x.m_twist); +} + +Odometry& Odometry::operator =( + const Odometry& x) +{ + + m_header = x.m_header; + m_child_frame_id = x.m_child_frame_id; + m_pose = x.m_pose; + m_twist = x.m_twist; + return *this; +} + +Odometry& Odometry::operator =( + Odometry&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_child_frame_id = std::move(x.m_child_frame_id); + m_pose = std::move(x.m_pose); + m_twist = std::move(x.m_twist); + return *this; +} + +bool Odometry::operator ==( + const Odometry& x) const +{ + return (m_header == x.m_header && + m_child_frame_id == x.m_child_frame_id && + m_pose == x.m_pose && + m_twist == x.m_twist); +} + +bool Odometry::operator !=( + const Odometry& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void Odometry::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 Odometry::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& Odometry::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& Odometry::header() +{ + return m_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 + */ +void Odometry::child_frame_id( + const std::string& _child_frame_id) +{ + m_child_frame_id = _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 + */ +void Odometry::child_frame_id( + std::string&& _child_frame_id) +{ + m_child_frame_id = std::move(_child_frame_id); +} + +/*! + * @brief This function returns a constant reference to member child_frame_id + * @return Constant reference to member child_frame_id + */ +const std::string& Odometry::child_frame_id() const +{ + return m_child_frame_id; +} + +/*! + * @brief This function returns a reference to member child_frame_id + * @return Reference to member child_frame_id + */ +std::string& Odometry::child_frame_id() +{ + return m_child_frame_id; +} + + +/*! + * @brief This function copies the value in member pose + * @param _pose New value to be copied in member pose + */ +void Odometry::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 Odometry::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& Odometry::pose() const +{ + return m_pose; +} + +/*! + * @brief This function returns a reference to member pose + * @return Reference to member pose + */ +geometry_msgs::msg::PoseWithCovariance& Odometry::pose() +{ + return m_pose; +} + + +/*! + * @brief This function copies the value in member twist + * @param _twist New value to be copied in member twist + */ +void Odometry::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 Odometry::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& Odometry::twist() const +{ + return m_twist; +} + +/*! + * @brief This function returns a reference to member twist + * @return Reference to member twist + */ +geometry_msgs::msg::TwistWithCovariance& Odometry::twist() +{ + return m_twist; +} + + + + +} // namespace msg + + +} // namespace nav_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "OdometryCdrAux.ipp" + 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..ae8e930fcb4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/Odometry.h @@ -0,0 +1,263 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_H_ +#define _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "geometry_msgs/msg/PoseWithCovariance.h" +#include "geometry_msgs/msg/TwistWithCovariance.h" +#include "std_msgs/msg/Header.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(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; +class CdrSizeCalculator; +} // 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(); + +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/fastdds/nav_msgs/msg/OdometryCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryCdrAux.hpp new file mode 100644 index 00000000000..300a7bd5e16 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file OdometryCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRYCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRYCDRAUX_HPP_ + +#include "Odometry.h" + +constexpr uint32_t nav_msgs_msg_Odometry_max_cdr_typesize {1264UL}; +constexpr uint32_t nav_msgs_msg_Odometry_max_key_cdr_typesize {0UL}; + + + + + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const nav_msgs::msg::Odometry& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRYCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryCdrAux.ipp new file mode 100644 index 00000000000..cc70b44a6c4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryCdrAux.ipp @@ -0,0 +1,154 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file OdometryCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRYCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRYCDRAUX_IPP_ + +#include "OdometryCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const nav_msgs::msg::Odometry& data, + size_t& current_alignment) +{ + using namespace nav_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.child_frame_id(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.pose(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.twist(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const nav_msgs::msg::Odometry& data) +{ + using namespace nav_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.child_frame_id() + << eprosima::fastcdr::MemberId(2) << data.pose() + << eprosima::fastcdr::MemberId(3) << data.twist() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + nav_msgs::msg::Odometry& data) +{ + using namespace nav_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.child_frame_id(); + break; + + case 2: + dcdr >> data.pose(); + break; + + case 3: + dcdr >> data.twist(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const nav_msgs::msg::Odometry& data) +{ + using namespace nav_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRYCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryPubSubTypes.cxx new file mode 100644 index 00000000000..b02dcb1bda6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryPubSubTypes.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 OdometryPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "OdometryPubSubTypes.h" +#include "OdometryCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace nav_msgs { +namespace msg { + + +OdometryPubSubType::OdometryPubSubType() +{ + setName("nav_msgs::msg::dds_::Odometry_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Odometry::getMaxCdrSerializedSize()); +#else + nav_msgs_msg_Odometry_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +OdometryPubSubType::~OdometryPubSubType() +{ +} + +bool OdometryPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Odometry* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool OdometryPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + Odometry* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function OdometryPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* OdometryPubSubType::createData() +{ + return reinterpret_cast(new Odometry()); +} + +void OdometryPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool OdometryPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace nav_msgs + 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..ac0558d1e8a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/nav_msgs/msg/OdometryPubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#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 != 2) +#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 ~OdometryPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace nav_msgs + +#endif // _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/post_process_generated_files.bash b/LibCarla/source/carla/ros2/fastdds/post_process_generated_files.bash new file mode 100755 index 00000000000..57616641846 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/post_process_generated_files.bash @@ -0,0 +1,25 @@ +#!/bin/bash + +# --- Configuration --- +# Set the directory where your generated files are located. +# "." means the current directory. +TARGET_DIR="." + +# --- Replacement Rules --- +# Rule 1: ' BEFORE_DECLARATION' -> ' PlacementKind::BEFORE_DECLARATION' +# Rule 2: 'PlacementKindValue' -> 'PlacementKind' +# Rule 3. 'BLABLA' (temporary type/name fixes) -> '' (remove this) +# Rule 4. '""' (empty quotes) -> '"' (single quotes) + +echo "Starting post-processing of Fast DDS generated files in: $TARGET_DIR" + +# We use find to target only relevant source/header files. +# -i is for in-place editing. +# We use a '|' as a separator in sed to handle spaces safely. +find "$TARGET_DIR" -type f \( -name "*.h" -o -name "*.hpp" -o -name "*.ipp" -o -name "*.cxx" -o -name "*.cpp" \) -print0 | xargs -0 sed -i \ + -e 's|BLABLA||g' \ + -e 's| BEFORE_DECLARATION| PlacementKind::BEFORE_DECLARATION|g' \ + -e 's|PlacementKindValue|PlacementKind|g' \ + -e 's|\"\"|"|g' \ + +echo "Done! Processed $(find "$TARGET_DIR" -type f \( -name "*.h" -o -name "*.hpp" -o -name "*.ipp" -o -name "*.cxx" -o -name "*.cpp" \) | wc -l) files." diff --git a/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/Clock.cxx b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/Clock.cxx new file mode 100644 index 00000000000..e660f6576b9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/Clock.cxx @@ -0,0 +1,141 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Clock.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace rosgraph_msgs { + +namespace msg { + + + +Clock::Clock() +{ +} + +Clock::~Clock() +{ +} + +Clock::Clock( + const Clock& x) +{ + m_clock = x.m_clock; +} + +Clock::Clock( + Clock&& x) noexcept +{ + m_clock = std::move(x.m_clock); +} + +Clock& Clock::operator =( + const Clock& x) +{ + + m_clock = x.m_clock; + return *this; +} + +Clock& Clock::operator =( + Clock&& x) noexcept +{ + + m_clock = std::move(x.m_clock); + return *this; +} + +bool Clock::operator ==( + const Clock& x) const +{ + return (m_clock == x.m_clock); +} + +bool Clock::operator !=( + const Clock& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member clock + * @param _clock New value to be copied in member clock + */ +void Clock::clock( + const builtin_interfaces::msg::Time& _clock) +{ + m_clock = _clock; +} + +/*! + * @brief This function moves the value in member clock + * @param _clock New value to be moved in member clock + */ +void Clock::clock( + builtin_interfaces::msg::Time&& _clock) +{ + m_clock = std::move(_clock); +} + +/*! + * @brief This function returns a constant reference to member clock + * @return Constant reference to member clock + */ +const builtin_interfaces::msg::Time& Clock::clock() const +{ + return m_clock; +} + +/*! + * @brief This function returns a reference to member clock + * @return Reference to member clock + */ +builtin_interfaces::msg::Time& Clock::clock() +{ + return m_clock; +} + + + + +} // namespace msg + + +} // namespace rosgraph_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ClockCdrAux.ipp" + 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..af85a0b8e53 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/Clock.h @@ -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 Clock.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCK_H_ +#define _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCK_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "builtin_interfaces/msg/Time.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(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; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace rosgraph_msgs { + +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_msgs::msg::Clock that will be copied. + */ + eProsima_user_DllExport Clock( + const Clock& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object rosgraph_msgs::msg::Clock that will be copied. + */ + eProsima_user_DllExport Clock( + Clock&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object rosgraph_msgs::msg::Clock that will be copied. + */ + eProsima_user_DllExport Clock& operator =( + const Clock& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object rosgraph_msgs::msg::Clock that will be copied. + */ + eProsima_user_DllExport Clock& operator =( + Clock&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x rosgraph_msgs::msg::Clock object to compare. + */ + eProsima_user_DllExport bool operator ==( + const Clock& x) const; + + /*! + * @brief Comparison operator. + * @param x rosgraph_msgs::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(); + +private: + + builtin_interfaces::msg::Time m_clock; + +}; + +} // namespace msg + +} // namespace rosgraph_msgs + +#endif // _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCK_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockCdrAux.hpp new file mode 100644 index 00000000000..3030113ca7a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ClockCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCKCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCKCDRAUX_HPP_ + +#include "Clock.h" + +constexpr uint32_t rosgraph_msgs_msg_Clock_max_cdr_typesize {16UL}; +constexpr uint32_t rosgraph_msgs_msg_Clock_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const rosgraph_msgs::msg::Clock& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCKCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockCdrAux.ipp new file mode 100644 index 00000000000..f54406a13f4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockCdrAux.ipp @@ -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 ClockCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCKCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCKCDRAUX_IPP_ + +#include "ClockCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const rosgraph_msgs::msg::Clock& data, + size_t& current_alignment) +{ + using namespace rosgraph_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.clock(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const rosgraph_msgs::msg::Clock& data) +{ + using namespace rosgraph_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.clock() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + rosgraph_msgs::msg::Clock& data) +{ + using namespace rosgraph_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.clock(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const rosgraph_msgs::msg::Clock& data) +{ + using namespace rosgraph_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCKCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockPubSubTypes.cxx new file mode 100644 index 00000000000..2e7131f17c3 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockPubSubTypes.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 ClockPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ClockPubSubTypes.h" +#include "ClockCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace rosgraph_msgs { +namespace msg { + + +ClockPubSubType::ClockPubSubType() +{ + setName("rosgraph_msgs::msg::dds_::Clock_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Clock::getMaxCdrSerializedSize()); +#else + rosgraph_msgs_msg_Clock_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ClockPubSubType::~ClockPubSubType() +{ +} + +bool ClockPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Clock* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ClockPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + Clock* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ClockPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* ClockPubSubType::createData() +{ + return reinterpret_cast(new Clock()); +} + +void ClockPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool ClockPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace rosgraph_msgs + 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..22785644006 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/rosgraph_msgs/msg/ClockPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCK_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCK_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Clock.h" + +#include "builtin_interfaces/msg/TimePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#error \ + Generated Clock is not compatible with current installed Fast DDS. Please, regenerate it with fastddsgen. +#endif // GEN_API_VER + +namespace rosgraph_msgs { +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 ~ClockPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace rosgraph_msgs + +#endif // _FAST_DDS_GENERATED_ROSGRAPH_MSGS_MSG_CLOCK_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfo.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfo.cxx new file mode 100644 index 00000000000..93c3c376713 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfo.cxx @@ -0,0 +1,541 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "CameraInfo.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace sensor_msgs { + +namespace msg { + + + +CameraInfo::CameraInfo() +{ +} + +CameraInfo::~CameraInfo() +{ +} + +CameraInfo::CameraInfo( + const CameraInfo& x) +{ + m_header = x.m_header; + m_height = x.m_height; + m_width = x.m_width; + m_distortion_model = x.m_distortion_model; + m_d = x.m_d; + m_k = x.m_k; + m_r = x.m_r; + m_p = x.m_p; + m_binning_x = x.m_binning_x; + m_binning_y = x.m_binning_y; + m_roi = x.m_roi; +} + +CameraInfo::CameraInfo( + CameraInfo&& x) noexcept +{ + m_header = std::move(x.m_header); + m_height = x.m_height; + m_width = x.m_width; + m_distortion_model = std::move(x.m_distortion_model); + m_d = std::move(x.m_d); + m_k = std::move(x.m_k); + m_r = std::move(x.m_r); + m_p = std::move(x.m_p); + m_binning_x = x.m_binning_x; + m_binning_y = x.m_binning_y; + m_roi = std::move(x.m_roi); +} + +CameraInfo& CameraInfo::operator =( + const CameraInfo& x) +{ + + m_header = x.m_header; + m_height = x.m_height; + m_width = x.m_width; + m_distortion_model = x.m_distortion_model; + m_d = x.m_d; + m_k = x.m_k; + m_r = x.m_r; + m_p = x.m_p; + m_binning_x = x.m_binning_x; + m_binning_y = x.m_binning_y; + m_roi = x.m_roi; + return *this; +} + +CameraInfo& CameraInfo::operator =( + CameraInfo&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_height = x.m_height; + m_width = x.m_width; + m_distortion_model = std::move(x.m_distortion_model); + m_d = std::move(x.m_d); + m_k = std::move(x.m_k); + m_r = std::move(x.m_r); + m_p = std::move(x.m_p); + m_binning_x = x.m_binning_x; + m_binning_y = x.m_binning_y; + m_roi = std::move(x.m_roi); + return *this; +} + +bool CameraInfo::operator ==( + const CameraInfo& x) const +{ + return (m_header == x.m_header && + m_height == x.m_height && + m_width == x.m_width && + m_distortion_model == x.m_distortion_model && + m_d == x.m_d && + m_k == x.m_k && + m_r == x.m_r && + m_p == x.m_p && + m_binning_x == x.m_binning_x && + m_binning_y == x.m_binning_y && + m_roi == x.m_roi); +} + +bool CameraInfo::operator !=( + const CameraInfo& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void CameraInfo::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 CameraInfo::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& CameraInfo::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& CameraInfo::header() +{ + return m_header; +} + + +/*! + * @brief This function sets a value in member height + * @param _height New value for member height + */ +void CameraInfo::height( + uint32_t _height) +{ + m_height = _height; +} + +/*! + * @brief This function returns the value of member height + * @return Value of member height + */ +uint32_t CameraInfo::height() const +{ + return m_height; +} + +/*! + * @brief This function returns a reference to member height + * @return Reference to member height + */ +uint32_t& CameraInfo::height() +{ + return m_height; +} + + +/*! + * @brief This function sets a value in member width + * @param _width New value for member width + */ +void CameraInfo::width( + uint32_t _width) +{ + m_width = _width; +} + +/*! + * @brief This function returns the value of member width + * @return Value of member width + */ +uint32_t CameraInfo::width() const +{ + return m_width; +} + +/*! + * @brief This function returns a reference to member width + * @return Reference to member width + */ +uint32_t& CameraInfo::width() +{ + return m_width; +} + + +/*! + * @brief This function copies the value in member distortion_model + * @param _distortion_model New value to be copied in member distortion_model + */ +void CameraInfo::distortion_model( + const std::string& _distortion_model) +{ + m_distortion_model = _distortion_model; +} + +/*! + * @brief This function moves the value in member distortion_model + * @param _distortion_model New value to be moved in member distortion_model + */ +void CameraInfo::distortion_model( + std::string&& _distortion_model) +{ + m_distortion_model = std::move(_distortion_model); +} + +/*! + * @brief This function returns a constant reference to member distortion_model + * @return Constant reference to member distortion_model + */ +const std::string& CameraInfo::distortion_model() const +{ + return m_distortion_model; +} + +/*! + * @brief This function returns a reference to member distortion_model + * @return Reference to member distortion_model + */ +std::string& CameraInfo::distortion_model() +{ + return m_distortion_model; +} + + +/*! + * @brief This function copies the value in member d + * @param _d New value to be copied in member d + */ +void CameraInfo::d( + const std::vector& _d) +{ + m_d = _d; +} + +/*! + * @brief This function moves the value in member d + * @param _d New value to be moved in member d + */ +void CameraInfo::d( + std::vector&& _d) +{ + m_d = std::move(_d); +} + +/*! + * @brief This function returns a constant reference to member d + * @return Constant reference to member d + */ +const std::vector& CameraInfo::d() const +{ + return m_d; +} + +/*! + * @brief This function returns a reference to member d + * @return Reference to member d + */ +std::vector& CameraInfo::d() +{ + return m_d; +} + + +/*! + * @brief This function copies the value in member k + * @param _k New value to be copied in member k + */ +void CameraInfo::k( + const sensor_msgs::msg::double__9& _k) +{ + m_k = _k; +} + +/*! + * @brief This function moves the value in member k + * @param _k New value to be moved in member k + */ +void CameraInfo::k( + sensor_msgs::msg::double__9&& _k) +{ + m_k = std::move(_k); +} + +/*! + * @brief This function returns a constant reference to member k + * @return Constant reference to member k + */ +const sensor_msgs::msg::double__9& CameraInfo::k() const +{ + return m_k; +} + +/*! + * @brief This function returns a reference to member k + * @return Reference to member k + */ +sensor_msgs::msg::double__9& CameraInfo::k() +{ + return m_k; +} + + +/*! + * @brief This function copies the value in member r + * @param _r New value to be copied in member r + */ +void CameraInfo::r( + const sensor_msgs::msg::double__9& _r) +{ + m_r = _r; +} + +/*! + * @brief This function moves the value in member r + * @param _r New value to be moved in member r + */ +void CameraInfo::r( + sensor_msgs::msg::double__9&& _r) +{ + m_r = std::move(_r); +} + +/*! + * @brief This function returns a constant reference to member r + * @return Constant reference to member r + */ +const sensor_msgs::msg::double__9& CameraInfo::r() const +{ + return m_r; +} + +/*! + * @brief This function returns a reference to member r + * @return Reference to member r + */ +sensor_msgs::msg::double__9& CameraInfo::r() +{ + return m_r; +} + + +/*! + * @brief This function copies the value in member p + * @param _p New value to be copied in member p + */ +void CameraInfo::p( + const sensor_msgs::msg::double__12& _p) +{ + m_p = _p; +} + +/*! + * @brief This function moves the value in member p + * @param _p New value to be moved in member p + */ +void CameraInfo::p( + sensor_msgs::msg::double__12&& _p) +{ + m_p = std::move(_p); +} + +/*! + * @brief This function returns a constant reference to member p + * @return Constant reference to member p + */ +const sensor_msgs::msg::double__12& CameraInfo::p() const +{ + return m_p; +} + +/*! + * @brief This function returns a reference to member p + * @return Reference to member p + */ +sensor_msgs::msg::double__12& CameraInfo::p() +{ + return m_p; +} + + +/*! + * @brief This function sets a value in member binning_x + * @param _binning_x New value for member binning_x + */ +void CameraInfo::binning_x( + uint32_t _binning_x) +{ + m_binning_x = _binning_x; +} + +/*! + * @brief This function returns the value of member binning_x + * @return Value of member binning_x + */ +uint32_t CameraInfo::binning_x() const +{ + return m_binning_x; +} + +/*! + * @brief This function returns a reference to member binning_x + * @return Reference to member binning_x + */ +uint32_t& CameraInfo::binning_x() +{ + return m_binning_x; +} + + +/*! + * @brief This function sets a value in member binning_y + * @param _binning_y New value for member binning_y + */ +void CameraInfo::binning_y( + uint32_t _binning_y) +{ + m_binning_y = _binning_y; +} + +/*! + * @brief This function returns the value of member binning_y + * @return Value of member binning_y + */ +uint32_t CameraInfo::binning_y() const +{ + return m_binning_y; +} + +/*! + * @brief This function returns a reference to member binning_y + * @return Reference to member binning_y + */ +uint32_t& CameraInfo::binning_y() +{ + return m_binning_y; +} + + +/*! + * @brief This function copies the value in member roi + * @param _roi New value to be copied in member roi + */ +void CameraInfo::roi( + const sensor_msgs::msg::RegionOfInterest& _roi) +{ + m_roi = _roi; +} + +/*! + * @brief This function moves the value in member roi + * @param _roi New value to be moved in member roi + */ +void CameraInfo::roi( + sensor_msgs::msg::RegionOfInterest&& _roi) +{ + m_roi = std::move(_roi); +} + +/*! + * @brief This function returns a constant reference to member roi + * @return Constant reference to member roi + */ +const sensor_msgs::msg::RegionOfInterest& CameraInfo::roi() const +{ + return m_roi; +} + +/*! + * @brief This function returns a reference to member roi + * @return Reference to member roi + */ +sensor_msgs::msg::RegionOfInterest& CameraInfo::roi() +{ + return m_roi; +} + + + + +} // namespace msg + + +} // namespace sensor_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "CameraInfoCdrAux.ipp" + 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..e98dfe68f41 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfo.h @@ -0,0 +1,434 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "RegionOfInterest.h" +#include "std_msgs/msg/Header.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(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; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace sensor_msgs { + +namespace msg { + +typedef std::array double__9; + +typedef std::array double__12; + + + +/*! + * @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(); + + /*! + * @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 sensor_msgs::msg::double__9& _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( + sensor_msgs::msg::double__9&& _k); + + /*! + * @brief This function returns a constant reference to member k + * @return Constant reference to member k + */ + eProsima_user_DllExport const sensor_msgs::msg::double__9& k() const; + + /*! + * @brief This function returns a reference to member k + * @return Reference to member k + */ + eProsima_user_DllExport sensor_msgs::msg::double__9& 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 sensor_msgs::msg::double__9& _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( + sensor_msgs::msg::double__9&& _r); + + /*! + * @brief This function returns a constant reference to member r + * @return Constant reference to member r + */ + eProsima_user_DllExport const sensor_msgs::msg::double__9& r() const; + + /*! + * @brief This function returns a reference to member r + * @return Reference to member r + */ + eProsima_user_DllExport sensor_msgs::msg::double__9& 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 sensor_msgs::msg::double__12& _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( + sensor_msgs::msg::double__12&& _p); + + /*! + * @brief This function returns a constant reference to member p + * @return Constant reference to member p + */ + eProsima_user_DllExport const sensor_msgs::msg::double__12& p() const; + + /*! + * @brief This function returns a reference to member p + * @return Reference to member p + */ + eProsima_user_DllExport sensor_msgs::msg::double__12& 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(); + +private: + + std_msgs::msg::Header m_header; + uint32_t m_height{0}; + uint32_t m_width{0}; + std::string m_distortion_model; + std::vector m_d; + sensor_msgs::msg::double__9 m_k{0.0}; + sensor_msgs::msg::double__9 m_r{0.0}; + sensor_msgs::msg::double__12 m_p{0.0}; + uint32_t m_binning_x{0}; + uint32_t m_binning_y{0}; + 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/fastdds/sensor_msgs/msg/CameraInfoCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoCdrAux.hpp new file mode 100644 index 00000000000..085aa067a71 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoCdrAux.hpp @@ -0,0 +1,57 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file CameraInfoCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFOCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFOCDRAUX_HPP_ + +#include "CameraInfo.h" + +constexpr uint32_t sensor_msgs_msg_CameraInfo_max_cdr_typesize {1621UL}; +constexpr uint32_t sensor_msgs_msg_CameraInfo_max_key_cdr_typesize {0UL}; + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::CameraInfo& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFOCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoCdrAux.ipp new file mode 100644 index 00000000000..6e9aa250cd9 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoCdrAux.ipp @@ -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 CameraInfoCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFOCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFOCDRAUX_IPP_ + +#include "CameraInfoCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const sensor_msgs::msg::CameraInfo& data, + size_t& current_alignment) +{ + using namespace sensor_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.height(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.width(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.distortion_model(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.d(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.k(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.r(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.p(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.binning_x(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(9), + data.binning_y(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(10), + data.roi(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::CameraInfo& data) +{ + using namespace sensor_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.height() + << eprosima::fastcdr::MemberId(2) << data.width() + << eprosima::fastcdr::MemberId(3) << data.distortion_model() + << eprosima::fastcdr::MemberId(4) << data.d() + << eprosima::fastcdr::MemberId(5) << data.k() + << eprosima::fastcdr::MemberId(6) << data.r() + << eprosima::fastcdr::MemberId(7) << data.p() + << eprosima::fastcdr::MemberId(8) << data.binning_x() + << eprosima::fastcdr::MemberId(9) << data.binning_y() + << eprosima::fastcdr::MemberId(10) << data.roi() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + sensor_msgs::msg::CameraInfo& data) +{ + using namespace sensor_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.height(); + break; + + case 2: + dcdr >> data.width(); + break; + + case 3: + dcdr >> data.distortion_model(); + break; + + case 4: + dcdr >> data.d(); + break; + + case 5: + dcdr >> data.k(); + break; + + case 6: + dcdr >> data.r(); + break; + + case 7: + dcdr >> data.p(); + break; + + case 8: + dcdr >> data.binning_x(); + break; + + case 9: + dcdr >> data.binning_y(); + break; + + case 10: + dcdr >> data.roi(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::CameraInfo& data) +{ + using namespace sensor_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFOCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoPubSubTypes.cxx new file mode 100644 index 00000000000..87aff85deaa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoPubSubTypes.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 CameraInfoPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "CameraInfoPubSubTypes.h" +#include "CameraInfoCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace sensor_msgs { +namespace msg { + + + + + + +CameraInfoPubSubType::CameraInfoPubSubType() +{ + setName("sensor_msgs::msg::dds_::CameraInfo_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(CameraInfo::getMaxCdrSerializedSize()); +#else + sensor_msgs_msg_CameraInfo_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +CameraInfoPubSubType::~CameraInfoPubSubType() +{ +} + +bool CameraInfoPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + CameraInfo* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool CameraInfoPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + CameraInfo* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function CameraInfoPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* CameraInfoPubSubType::createData() +{ + return reinterpret_cast(new CameraInfo()); +} + +void CameraInfoPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool CameraInfoPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace sensor_msgs + 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..971869b6c79 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/CameraInfoPubSubTypes.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 CameraInfoPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "CameraInfo.h" + +#include "RegionOfInterestPubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { +typedef std::array double__9; +typedef std::array double__12; + + + +/*! + * @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 ~CameraInfoPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // 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..fe57b4ae583 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Image.cc @@ -0,0 +1,425 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace sensor_msgs { + +namespace msg { + + + + + +template +ImageT::ImageT() +{ +} + +template +ImageT::~ImageT() +{ +} + +template +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 +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 +ImageT& +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 +ImageT& +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 +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 +ImageT::operator !=( + const ImageT& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +template +void +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 +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& +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& +ImageT::header() +{ + return m_header; +} + + +/*! + * @brief This function sets a value in member height + * @param _height New value for member height + */ +template +void +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 +ImageT::height() const +{ + return m_height; +} + +/*! + * @brief This function returns a reference to member height + * @return Reference to member height + */ +template +uint32_t& +ImageT::height() +{ + return m_height; +} + + +/*! + * @brief This function sets a value in member width + * @param _width New value for member width + */ +template +void +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 +ImageT::width() const +{ + return m_width; +} + +/*! + * @brief This function returns a reference to member width + * @return Reference to member width + */ +template +uint32_t& +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 +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 +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& +ImageT::encoding() const +{ + return m_encoding; +} + +/*! + * @brief This function returns a reference to member encoding + * @return Reference to member encoding + */ +template +std::string& +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 +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 +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& +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 +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 +ImageT::step() const +{ + return m_step; +} + +/*! + * @brief This function returns a reference to member step + * @return Reference to member step + */ +template +uint32_t& +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 +ImageT::data( + const typename 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 +ImageT::data( + typename 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 ImageT::vector_type& +ImageT::data() const +{ + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +template +typename ImageT::vector_type& +ImageT::data() +{ + return m_data; +} + + + + +} // namespace msg + + +} // namespace sensor_msgs + 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..abc5af40391 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Image.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 Image.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "std_msgs/msg/Header.h" +#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(IMAGE_SOURCE) +#define IMAGE_DllAPI __declspec( dllexport ) +#else +#define IMAGE_DllAPI __declspec( dllimport ) +#endif // IMAGE_SOURCE +#else +#define IMAGE_DllAPI +#endif // EPROSIMA_USER_DLL_EXPORT +#else +#define IMAGE_DllAPI +#endif // _WIN32 + +namespace eprosima { +namespace fastcdr { +class Cdr; +class CdrSizeCalculator; +} // 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(); + +private: + + std_msgs::msg::Header m_header; + uint32_t m_height{0}; + uint32_t m_width{0}; + std::string m_encoding; + uint8_t m_is_bigendian{0}; + uint32_t m_step{0}; + vector_type m_data; + +}; + + +using ImageFromBuffer = ImageT>; +using Image = ImageT>; + +} // namespace msg + +} // namespace sensor_msgs + +#include "Image.cc" + +#endif // _FAST_DDS_G>ENERATED_SENSOR_MSGS_MSG_IMAGE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImageCdrAux.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImageCdrAux.cxx new file mode 100644 index 00000000000..4a032213a48 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImageCdrAux.cxx @@ -0,0 +1,180 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ImageCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGECDRAUX_IPP_ + +#include "ImageCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const sensor_msgs::msg::Image& data, + size_t& current_alignment) +{ + using namespace sensor_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.height(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.width(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.encoding(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.is_bigendian(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.step(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.data(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::Image& data) +{ + using namespace sensor_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.height() + << eprosima::fastcdr::MemberId(2) << data.width() + << eprosima::fastcdr::MemberId(3) << data.encoding() + << eprosima::fastcdr::MemberId(4) << data.is_bigendian() + << eprosima::fastcdr::MemberId(5) << data.step() + << eprosima::fastcdr::MemberId(6) << data.data() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + sensor_msgs::msg::Image& data) +{ + using namespace sensor_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.height(); + break; + + case 2: + dcdr >> data.width(); + break; + + case 3: + dcdr >> data.encoding(); + break; + + case 4: + dcdr >> data.is_bigendian(); + break; + + case 5: + dcdr >> data.step(); + break; + + case 6: + dcdr >> data.data(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::Image& data) +{ + using namespace sensor_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGECDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImageCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImageCdrAux.hpp new file mode 100644 index 00000000000..4143c62c980 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImageCdrAux.hpp @@ -0,0 +1,53 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ImageCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGECDRAUX_HPP_ + +#include "Image.h" + +constexpr uint32_t sensor_msgs_msg_Image_max_cdr_typesize {660UL}; +constexpr uint32_t sensor_msgs_msg_Image_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::Image& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImageCdrAuxFromBuffer.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImageCdrAuxFromBuffer.cxx new file mode 100644 index 00000000000..bf32e2bd1f2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImageCdrAuxFromBuffer.cxx @@ -0,0 +1,180 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ImageCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGECDRAUX_IPP_ + +#include "ImageCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const sensor_msgs::msg::ImageFromBuffer& data, + size_t& current_alignment) +{ + using namespace sensor_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.height(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.width(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.encoding(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.is_bigendian(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.step(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.data(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::ImageFromBuffer& data) +{ + using namespace sensor_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.height() + << eprosima::fastcdr::MemberId(2) << data.width() + << eprosima::fastcdr::MemberId(3) << data.encoding() + << eprosima::fastcdr::MemberId(4) << data.is_bigendian() + << eprosima::fastcdr::MemberId(5) << data.step() + << eprosima::fastcdr::MemberId(6) << data.data() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + sensor_msgs::msg::ImageFromBuffer& data) +{ + using namespace sensor_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.height(); + break; + + case 2: + dcdr >> data.width(); + break; + + case 3: + dcdr >> data.encoding(); + break; + + case 4: + dcdr >> data.is_bigendian(); + break; + + case 5: + dcdr >> data.step(); + break; + + case 6: + dcdr >> data.data(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::ImageFromBuffer& data) +{ + using namespace sensor_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGECDRAUX_IPP_ + 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..e493315b7c8 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImagePubSubTypes.cc @@ -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 ImagePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ImagePubSubTypes.h" +#include "ImageCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace sensor_msgs { +namespace msg { + + + + +template +ImagePubSubTypeT::ImagePubSubTypeT() +{ + setName("sensor_msgs::msg::dds_::Image_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(type::getMaxCdrSerializedSize()); +#else + sensor_msgs_msg_Image_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +template +ImagePubSubTypeT::~ImagePubSubTypeT() +{ +} + +template bool +ImagePubSubTypeT::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +template bool +ImagePubSubTypeT::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +template std::function +ImagePubSubTypeT::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..0b6f9691f4c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImagePubSubTypes.h @@ -0,0 +1,140 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ImagePubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Image.h" + +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ::sensor_msgs::msg::ImageT type; + + eProsima_user_DllExport ImagePubSubTypeT(); + + eProsima_user_DllExport ~ImagePubSubTypeT() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // 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/fastdds/sensor_msgs/msg/Imu.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Imu.cxx new file mode 100644 index 00000000000..4300803b43c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Imu.cxx @@ -0,0 +1,405 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Imu.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace sensor_msgs { + +namespace msg { + + + +Imu::Imu() +{ +} + +Imu::~Imu() +{ +} + +Imu::Imu( + const Imu& x) +{ + m_header = x.m_header; + m_orientation = x.m_orientation; + m_orientation_covariance = x.m_orientation_covariance; + m_angular_velocity = x.m_angular_velocity; + m_angular_velocity_covariance = x.m_angular_velocity_covariance; + m_linear_acceleration = x.m_linear_acceleration; + m_linear_acceleration_covariance = x.m_linear_acceleration_covariance; +} + +Imu::Imu( + Imu&& x) noexcept +{ + m_header = std::move(x.m_header); + m_orientation = std::move(x.m_orientation); + m_orientation_covariance = std::move(x.m_orientation_covariance); + m_angular_velocity = std::move(x.m_angular_velocity); + m_angular_velocity_covariance = std::move(x.m_angular_velocity_covariance); + m_linear_acceleration = std::move(x.m_linear_acceleration); + m_linear_acceleration_covariance = std::move(x.m_linear_acceleration_covariance); +} + +Imu& Imu::operator =( + const Imu& x) +{ + + m_header = x.m_header; + m_orientation = x.m_orientation; + m_orientation_covariance = x.m_orientation_covariance; + m_angular_velocity = x.m_angular_velocity; + m_angular_velocity_covariance = x.m_angular_velocity_covariance; + m_linear_acceleration = x.m_linear_acceleration; + m_linear_acceleration_covariance = x.m_linear_acceleration_covariance; + return *this; +} + +Imu& Imu::operator =( + Imu&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_orientation = std::move(x.m_orientation); + m_orientation_covariance = std::move(x.m_orientation_covariance); + m_angular_velocity = std::move(x.m_angular_velocity); + m_angular_velocity_covariance = std::move(x.m_angular_velocity_covariance); + m_linear_acceleration = std::move(x.m_linear_acceleration); + m_linear_acceleration_covariance = std::move(x.m_linear_acceleration_covariance); + return *this; +} + +bool Imu::operator ==( + const Imu& x) const +{ + return (m_header == x.m_header && + m_orientation == x.m_orientation && + m_orientation_covariance == x.m_orientation_covariance && + m_angular_velocity == x.m_angular_velocity && + m_angular_velocity_covariance == x.m_angular_velocity_covariance && + m_linear_acceleration == x.m_linear_acceleration && + m_linear_acceleration_covariance == x.m_linear_acceleration_covariance); +} + +bool Imu::operator !=( + const Imu& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void Imu::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 Imu::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& Imu::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& Imu::header() +{ + return m_header; +} + + +/*! + * @brief This function copies the value in member orientation + * @param _orientation New value to be copied in member orientation + */ +void Imu::orientation( + const geometry_msgs::msg::Quaternion& _orientation) +{ + m_orientation = _orientation; +} + +/*! + * @brief This function moves the value in member orientation + * @param _orientation New value to be moved in member orientation + */ +void Imu::orientation( + geometry_msgs::msg::Quaternion&& _orientation) +{ + m_orientation = std::move(_orientation); +} + +/*! + * @brief This function returns a constant reference to member orientation + * @return Constant reference to member orientation + */ +const geometry_msgs::msg::Quaternion& Imu::orientation() const +{ + return m_orientation; +} + +/*! + * @brief This function returns a reference to member orientation + * @return Reference to member orientation + */ +geometry_msgs::msg::Quaternion& Imu::orientation() +{ + return m_orientation; +} + + +/*! + * @brief This function copies the value in member orientation_covariance + * @param _orientation_covariance New value to be copied in member orientation_covariance + */ +void Imu::orientation_covariance( + const sensor_msgs::msg::double__9& _orientation_covariance) +{ + m_orientation_covariance = _orientation_covariance; +} + +/*! + * @brief This function moves the value in member orientation_covariance + * @param _orientation_covariance New value to be moved in member orientation_covariance + */ +void Imu::orientation_covariance( + sensor_msgs::msg::double__9&& _orientation_covariance) +{ + m_orientation_covariance = std::move(_orientation_covariance); +} + +/*! + * @brief This function returns a constant reference to member orientation_covariance + * @return Constant reference to member orientation_covariance + */ +const sensor_msgs::msg::double__9& Imu::orientation_covariance() const +{ + return m_orientation_covariance; +} + +/*! + * @brief This function returns a reference to member orientation_covariance + * @return Reference to member orientation_covariance + */ +sensor_msgs::msg::double__9& Imu::orientation_covariance() +{ + return m_orientation_covariance; +} + + +/*! + * @brief This function copies the value in member angular_velocity + * @param _angular_velocity New value to be copied in member angular_velocity + */ +void Imu::angular_velocity( + const geometry_msgs::msg::Vector3& _angular_velocity) +{ + m_angular_velocity = _angular_velocity; +} + +/*! + * @brief This function moves the value in member angular_velocity + * @param _angular_velocity New value to be moved in member angular_velocity + */ +void Imu::angular_velocity( + geometry_msgs::msg::Vector3&& _angular_velocity) +{ + m_angular_velocity = std::move(_angular_velocity); +} + +/*! + * @brief This function returns a constant reference to member angular_velocity + * @return Constant reference to member angular_velocity + */ +const geometry_msgs::msg::Vector3& Imu::angular_velocity() const +{ + return m_angular_velocity; +} + +/*! + * @brief This function returns a reference to member angular_velocity + * @return Reference to member angular_velocity + */ +geometry_msgs::msg::Vector3& Imu::angular_velocity() +{ + return m_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 + */ +void Imu::angular_velocity_covariance( + const sensor_msgs::msg::double__9& _angular_velocity_covariance) +{ + m_angular_velocity_covariance = _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 + */ +void Imu::angular_velocity_covariance( + sensor_msgs::msg::double__9&& _angular_velocity_covariance) +{ + m_angular_velocity_covariance = std::move(_angular_velocity_covariance); +} + +/*! + * @brief This function returns a constant reference to member angular_velocity_covariance + * @return Constant reference to member angular_velocity_covariance + */ +const sensor_msgs::msg::double__9& Imu::angular_velocity_covariance() const +{ + return m_angular_velocity_covariance; +} + +/*! + * @brief This function returns a reference to member angular_velocity_covariance + * @return Reference to member angular_velocity_covariance + */ +sensor_msgs::msg::double__9& Imu::angular_velocity_covariance() +{ + return m_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 + */ +void Imu::linear_acceleration( + const geometry_msgs::msg::Vector3& _linear_acceleration) +{ + m_linear_acceleration = _linear_acceleration; +} + +/*! + * @brief This function moves the value in member linear_acceleration + * @param _linear_acceleration New value to be moved in member linear_acceleration + */ +void Imu::linear_acceleration( + geometry_msgs::msg::Vector3&& _linear_acceleration) +{ + m_linear_acceleration = std::move(_linear_acceleration); +} + +/*! + * @brief This function returns a constant reference to member linear_acceleration + * @return Constant reference to member linear_acceleration + */ +const geometry_msgs::msg::Vector3& Imu::linear_acceleration() const +{ + return m_linear_acceleration; +} + +/*! + * @brief This function returns a reference to member linear_acceleration + * @return Reference to member linear_acceleration + */ +geometry_msgs::msg::Vector3& Imu::linear_acceleration() +{ + return m_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 + */ +void Imu::linear_acceleration_covariance( + const sensor_msgs::msg::double__9& _linear_acceleration_covariance) +{ + m_linear_acceleration_covariance = _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 + */ +void Imu::linear_acceleration_covariance( + sensor_msgs::msg::double__9&& _linear_acceleration_covariance) +{ + m_linear_acceleration_covariance = std::move(_linear_acceleration_covariance); +} + +/*! + * @brief This function returns a constant reference to member linear_acceleration_covariance + * @return Constant reference to member linear_acceleration_covariance + */ +const sensor_msgs::msg::double__9& Imu::linear_acceleration_covariance() const +{ + return m_linear_acceleration_covariance; +} + +/*! + * @brief This function returns a reference to member linear_acceleration_covariance + * @return Reference to member linear_acceleration_covariance + */ +sensor_msgs::msg::double__9& Imu::linear_acceleration_covariance() +{ + return m_linear_acceleration_covariance; +} + + + + +} // namespace msg + + +} // namespace sensor_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "ImuCdrAux.ipp" + 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..3440b6ba54b --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/Imu.h @@ -0,0 +1,349 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "geometry_msgs/msg/Vector3.h" +#include "geometry_msgs/msg/Quaternion.h" +#include "std_msgs/msg/Header.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(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; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace sensor_msgs { + +namespace msg { + +typedef std::array double__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::double__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::double__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::double__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::double__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::double__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::double__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::double__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::double__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::double__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::double__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::double__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::double__9& linear_acceleration_covariance(); + +private: + + std_msgs::msg::Header m_header; + geometry_msgs::msg::Quaternion m_orientation; + sensor_msgs::msg::double__9 m_orientation_covariance{0.0}; + geometry_msgs::msg::Vector3 m_angular_velocity; + sensor_msgs::msg::double__9 m_angular_velocity_covariance{0.0}; + geometry_msgs::msg::Vector3 m_linear_acceleration; + sensor_msgs::msg::double__9 m_linear_acceleration_covariance{0.0}; + +}; + +} // namespace msg + +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuCdrAux.hpp new file mode 100644 index 00000000000..3ea714c7465 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuCdrAux.hpp @@ -0,0 +1,52 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ImuCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMUCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMUCDRAUX_HPP_ + +#include "Imu.h" + +constexpr uint32_t sensor_msgs_msg_Imu_max_cdr_typesize {600UL}; +constexpr uint32_t sensor_msgs_msg_Imu_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::Imu& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMUCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuCdrAux.ipp new file mode 100644 index 00000000000..a8eeec8869c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuCdrAux.ipp @@ -0,0 +1,180 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file ImuCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMUCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMUCDRAUX_IPP_ + +#include "ImuCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const sensor_msgs::msg::Imu& data, + size_t& current_alignment) +{ + using namespace sensor_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.orientation(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.orientation_covariance(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.angular_velocity(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.angular_velocity_covariance(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.linear_acceleration(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.linear_acceleration_covariance(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::Imu& data) +{ + using namespace sensor_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.orientation() + << eprosima::fastcdr::MemberId(2) << data.orientation_covariance() + << eprosima::fastcdr::MemberId(3) << data.angular_velocity() + << eprosima::fastcdr::MemberId(4) << data.angular_velocity_covariance() + << eprosima::fastcdr::MemberId(5) << data.linear_acceleration() + << eprosima::fastcdr::MemberId(6) << data.linear_acceleration_covariance() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + sensor_msgs::msg::Imu& data) +{ + using namespace sensor_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.orientation(); + break; + + case 2: + dcdr >> data.orientation_covariance(); + break; + + case 3: + dcdr >> data.angular_velocity(); + break; + + case 4: + dcdr >> data.angular_velocity_covariance(); + break; + + case 5: + dcdr >> data.linear_acceleration(); + break; + + case 6: + dcdr >> data.linear_acceleration_covariance(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::Imu& data) +{ + using namespace sensor_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMUCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuPubSubTypes.cxx new file mode 100644 index 00000000000..accffceea2a --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuPubSubTypes.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 ImuPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "ImuPubSubTypes.h" +#include "ImuCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace sensor_msgs { +namespace msg { + + + + +ImuPubSubType::ImuPubSubType() +{ + setName("sensor_msgs::msg::dds_::Imu_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Imu::getMaxCdrSerializedSize()); +#else + sensor_msgs_msg_Imu_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +ImuPubSubType::~ImuPubSubType() +{ +} + +bool ImuPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Imu* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool ImuPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + Imu* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function ImuPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* ImuPubSubType::createData() +{ + return reinterpret_cast(new Imu()); +} + +void ImuPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool ImuPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace sensor_msgs + 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..5e67efeb06c --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/ImuPubSubTypes.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 ImuPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Imu.h" + +#include "geometry_msgs/msg/Vector3PubSubTypes.h" +#include "geometry_msgs/msg/QuaternionPubSubTypes.h" +#include "std_msgs/msg/HeaderPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 double__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 ~ImuPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMU_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFix.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFix.cxx new file mode 100644 index 00000000000..75ff43485e1 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFix.cxx @@ -0,0 +1,369 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "NavSatFix.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace sensor_msgs { + +namespace msg { + +namespace NavSatFix_Constants { + + +} // namespace NavSatFix_Constants + + +NavSatFix::NavSatFix() +{ +} + +NavSatFix::~NavSatFix() +{ +} + +NavSatFix::NavSatFix( + const NavSatFix& x) +{ + m_header = x.m_header; + m_status = x.m_status; + m_latitude = x.m_latitude; + m_longitude = x.m_longitude; + m_altitude = x.m_altitude; + m_position_covariance = x.m_position_covariance; + m_position_covariance_type = x.m_position_covariance_type; +} + +NavSatFix::NavSatFix( + NavSatFix&& x) noexcept +{ + m_header = std::move(x.m_header); + m_status = std::move(x.m_status); + m_latitude = x.m_latitude; + m_longitude = x.m_longitude; + m_altitude = x.m_altitude; + m_position_covariance = std::move(x.m_position_covariance); + m_position_covariance_type = x.m_position_covariance_type; +} + +NavSatFix& NavSatFix::operator =( + const NavSatFix& x) +{ + + m_header = x.m_header; + m_status = x.m_status; + m_latitude = x.m_latitude; + m_longitude = x.m_longitude; + m_altitude = x.m_altitude; + m_position_covariance = x.m_position_covariance; + m_position_covariance_type = x.m_position_covariance_type; + return *this; +} + +NavSatFix& NavSatFix::operator =( + NavSatFix&& x) noexcept +{ + + m_header = std::move(x.m_header); + m_status = std::move(x.m_status); + m_latitude = x.m_latitude; + m_longitude = x.m_longitude; + m_altitude = x.m_altitude; + m_position_covariance = std::move(x.m_position_covariance); + m_position_covariance_type = x.m_position_covariance_type; + return *this; +} + +bool NavSatFix::operator ==( + const NavSatFix& x) const +{ + return (m_header == x.m_header && + m_status == x.m_status && + m_latitude == x.m_latitude && + m_longitude == x.m_longitude && + m_altitude == x.m_altitude && + m_position_covariance == x.m_position_covariance && + m_position_covariance_type == x.m_position_covariance_type); +} + +bool NavSatFix::operator !=( + const NavSatFix& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void NavSatFix::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 NavSatFix::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& NavSatFix::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& NavSatFix::header() +{ + return m_header; +} + + +/*! + * @brief This function copies the value in member status + * @param _status New value to be copied in member status + */ +void NavSatFix::status( + const sensor_msgs::msg::NavSatStatus& _status) +{ + m_status = _status; +} + +/*! + * @brief This function moves the value in member status + * @param _status New value to be moved in member status + */ +void NavSatFix::status( + sensor_msgs::msg::NavSatStatus&& _status) +{ + m_status = std::move(_status); +} + +/*! + * @brief This function returns a constant reference to member status + * @return Constant reference to member status + */ +const sensor_msgs::msg::NavSatStatus& NavSatFix::status() const +{ + return m_status; +} + +/*! + * @brief This function returns a reference to member status + * @return Reference to member status + */ +sensor_msgs::msg::NavSatStatus& NavSatFix::status() +{ + return m_status; +} + + +/*! + * @brief This function sets a value in member latitude + * @param _latitude New value for member latitude + */ +void NavSatFix::latitude( + double _latitude) +{ + m_latitude = _latitude; +} + +/*! + * @brief This function returns the value of member latitude + * @return Value of member latitude + */ +double NavSatFix::latitude() const +{ + return m_latitude; +} + +/*! + * @brief This function returns a reference to member latitude + * @return Reference to member latitude + */ +double& NavSatFix::latitude() +{ + return m_latitude; +} + + +/*! + * @brief This function sets a value in member longitude + * @param _longitude New value for member longitude + */ +void NavSatFix::longitude( + double _longitude) +{ + m_longitude = _longitude; +} + +/*! + * @brief This function returns the value of member longitude + * @return Value of member longitude + */ +double NavSatFix::longitude() const +{ + return m_longitude; +} + +/*! + * @brief This function returns a reference to member longitude + * @return Reference to member longitude + */ +double& NavSatFix::longitude() +{ + return m_longitude; +} + + +/*! + * @brief This function sets a value in member altitude + * @param _altitude New value for member altitude + */ +void NavSatFix::altitude( + double _altitude) +{ + m_altitude = _altitude; +} + +/*! + * @brief This function returns the value of member altitude + * @return Value of member altitude + */ +double NavSatFix::altitude() const +{ + return m_altitude; +} + +/*! + * @brief This function returns a reference to member altitude + * @return Reference to member altitude + */ +double& NavSatFix::altitude() +{ + return m_altitude; +} + + +/*! + * @brief This function copies the value in member position_covariance + * @param _position_covariance New value to be copied in member position_covariance + */ +void NavSatFix::position_covariance( + const sensor_msgs::msg::double__9& _position_covariance) +{ + m_position_covariance = _position_covariance; +} + +/*! + * @brief This function moves the value in member position_covariance + * @param _position_covariance New value to be moved in member position_covariance + */ +void NavSatFix::position_covariance( + sensor_msgs::msg::double__9&& _position_covariance) +{ + m_position_covariance = std::move(_position_covariance); +} + +/*! + * @brief This function returns a constant reference to member position_covariance + * @return Constant reference to member position_covariance + */ +const sensor_msgs::msg::double__9& NavSatFix::position_covariance() const +{ + return m_position_covariance; +} + +/*! + * @brief This function returns a reference to member position_covariance + * @return Reference to member position_covariance + */ +sensor_msgs::msg::double__9& NavSatFix::position_covariance() +{ + return m_position_covariance; +} + + +/*! + * @brief This function sets a value in member position_covariance_type + * @param _position_covariance_type New value for member position_covariance_type + */ +void NavSatFix::position_covariance_type( + uint8_t _position_covariance_type) +{ + m_position_covariance_type = _position_covariance_type; +} + +/*! + * @brief This function returns the value of member position_covariance_type + * @return Value of member position_covariance_type + */ +uint8_t NavSatFix::position_covariance_type() const +{ + return m_position_covariance_type; +} + +/*! + * @brief This function returns a reference to member position_covariance_type + * @return Reference to member position_covariance_type + */ +uint8_t& NavSatFix::position_covariance_type() +{ + return m_position_covariance_type; +} + + + + +} // namespace msg + + +} // namespace sensor_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "NavSatFixCdrAux.ipp" + 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..8b565bbe162 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFix.h @@ -0,0 +1,328 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "std_msgs/msg/Header.h" +#include "NavSatStatus.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(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; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace sensor_msgs { + +namespace msg { + +typedef std::array double__9; + +namespace NavSatFix_Constants { + +const uint8_t COVARIANCE_TYPE_UNKNOWN = 0; +const uint8_t COVARIANCE_TYPE_APPROXIMATED = 1; +const uint8_t COVARIANCE_TYPE_DIAGONAL_KNOWN = 2; +const uint8_t COVARIANCE_TYPE_KNOWN = 3; + +} // namespace NavSatFix_Constants + + +/*! + * @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::double__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::double__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::double__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::double__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(); + +private: + + std_msgs::msg::Header m_header; + sensor_msgs::msg::NavSatStatus m_status; + double m_latitude{0.0}; + double m_longitude{0.0}; + double m_altitude{0.0}; + sensor_msgs::msg::double__9 m_position_covariance{0.0}; + uint8_t m_position_covariance_type{0}; + +}; + +} // namespace msg + +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixCdrAux.hpp new file mode 100644 index 00000000000..c6c78712895 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixCdrAux.hpp @@ -0,0 +1,61 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file NavSatFixCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIXCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIXCDRAUX_HPP_ + +#include "NavSatFix.h" + +constexpr uint32_t sensor_msgs_msg_NavSatFix_max_cdr_typesize {385UL}; +constexpr uint32_t sensor_msgs_msg_NavSatFix_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::NavSatFix& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIXCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixCdrAux.ipp new file mode 100644 index 00000000000..d0d37b1b403 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixCdrAux.ipp @@ -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 NavSatFixCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIXCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIXCDRAUX_IPP_ + +#include "NavSatFixCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const sensor_msgs::msg::NavSatFix& data, + size_t& current_alignment) +{ + using namespace sensor_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.status(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.latitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.longitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.altitude(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.position_covariance(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.position_covariance_type(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::NavSatFix& data) +{ + using namespace sensor_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.status() + << eprosima::fastcdr::MemberId(2) << data.latitude() + << eprosima::fastcdr::MemberId(3) << data.longitude() + << eprosima::fastcdr::MemberId(4) << data.altitude() + << eprosima::fastcdr::MemberId(5) << data.position_covariance() + << eprosima::fastcdr::MemberId(6) << data.position_covariance_type() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + sensor_msgs::msg::NavSatFix& data) +{ + using namespace sensor_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.status(); + break; + + case 2: + dcdr >> data.latitude(); + break; + + case 3: + dcdr >> data.longitude(); + break; + + case 4: + dcdr >> data.altitude(); + break; + + case 5: + dcdr >> data.position_covariance(); + break; + + case 6: + dcdr >> data.position_covariance_type(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::NavSatFix& data) +{ + using namespace sensor_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIXCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixPubSubTypes.cxx new file mode 100644 index 00000000000..449dfda8cb4 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixPubSubTypes.cxx @@ -0,0 +1,212 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "NavSatFixPubSubTypes.h" +#include "NavSatFixCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace sensor_msgs { +namespace msg { + + +namespace NavSatFix_Constants { + + + + + + + + + +} //End of namespace NavSatFix_Constants + + + +NavSatFixPubSubType::NavSatFixPubSubType() +{ + setName("sensor_msgs::msg::dds_::NavSatFix_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(NavSatFix::getMaxCdrSerializedSize()); +#else + sensor_msgs_msg_NavSatFix_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +NavSatFixPubSubType::~NavSatFixPubSubType() +{ +} + +bool NavSatFixPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + NavSatFix* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool NavSatFixPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + NavSatFix* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function NavSatFixPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* NavSatFixPubSubType::createData() +{ + return reinterpret_cast(new NavSatFix()); +} + +void NavSatFixPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool NavSatFixPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace sensor_msgs + 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..01e41641ccc --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatFixPubSubTypes.h @@ -0,0 +1,148 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "NavSatFix.h" + +#include "std_msgs/msg/HeaderPubSubTypes.h" +#include "NavSatStatusPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 double__9; +namespace NavSatFix_Constants { + + + + + + + + +} // namespace NavSatFix_Constants + + + +/*! + * @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 ~NavSatFixPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATFIX_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatus.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatus.cxx new file mode 100644 index 00000000000..b391e4c8b3f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatus.cxx @@ -0,0 +1,169 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "NavSatStatus.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace sensor_msgs { + +namespace msg { + +namespace NavSatStatus_Constants { + + +} // namespace NavSatStatus_Constants + + +NavSatStatus::NavSatStatus() +{ +} + +NavSatStatus::~NavSatStatus() +{ +} + +NavSatStatus::NavSatStatus( + const NavSatStatus& x) +{ + m_status = x.m_status; + m_service = x.m_service; +} + +NavSatStatus::NavSatStatus( + NavSatStatus&& x) noexcept +{ + m_status = x.m_status; + m_service = x.m_service; +} + +NavSatStatus& NavSatStatus::operator =( + const NavSatStatus& x) +{ + + m_status = x.m_status; + m_service = x.m_service; + return *this; +} + +NavSatStatus& NavSatStatus::operator =( + NavSatStatus&& x) noexcept +{ + + m_status = x.m_status; + m_service = x.m_service; + return *this; +} + +bool NavSatStatus::operator ==( + const NavSatStatus& x) const +{ + return (m_status == x.m_status && + m_service == x.m_service); +} + +bool NavSatStatus::operator !=( + const NavSatStatus& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member status + * @param _status New value for member status + */ +void NavSatStatus::status( + int8_t _status) +{ + m_status = _status; +} + +/*! + * @brief This function returns the value of member status + * @return Value of member status + */ +int8_t NavSatStatus::status() const +{ + return m_status; +} + +/*! + * @brief This function returns a reference to member status + * @return Reference to member status + */ +int8_t& NavSatStatus::status() +{ + return m_status; +} + + +/*! + * @brief This function sets a value in member service + * @param _service New value for member service + */ +void NavSatStatus::service( + uint16_t _service) +{ + m_service = _service; +} + +/*! + * @brief This function returns the value of member service + * @return Value of member service + */ +uint16_t NavSatStatus::service() const +{ + return m_service; +} + +/*! + * @brief This function returns a reference to member service + * @return Reference to member service + */ +uint16_t& NavSatStatus::service() +{ + return m_service; +} + + + + +} // namespace msg + + +} // namespace sensor_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "NavSatStatusCdrAux.ipp" + 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..c88f7b10b7f --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatus.h @@ -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 NavSatStatus.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 +#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; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace sensor_msgs { + +namespace msg { + +namespace NavSatStatus_Constants { + +const int8_t STATUS_UNKNOWN = -2; +const int8_t STATUS_NO_FIX = -1; +const int8_t STATUS_FIX = 0; +const int8_t STATUS_SBAS_FIX = 1; +const int8_t STATUS_GBAS_FIX = 2; +const uint16_t SERVICE_UNKNOWN = 0; +const uint16_t SERVICE_GPS = 1; +const uint16_t SERVICE_GLONASS = 2; +const uint16_t SERVICE_COMPASS = 4; +const uint16_t SERVICE_GALILEO = 8; + +} // namespace NavSatStatus_Constants + + +/*! + * @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( + int8_t _status); + + /*! + * @brief This function returns the value of member status + * @return Value of member status + */ + eProsima_user_DllExport int8_t status() const; + + /*! + * @brief This function returns a reference to member status + * @return Reference to member status + */ + eProsima_user_DllExport int8_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(); + +private: + + int8_t m_status{-2}; + uint16_t m_service{0}; + +}; + +} // namespace msg + +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusCdrAux.hpp new file mode 100644 index 00000000000..3933ca29e01 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusCdrAux.hpp @@ -0,0 +1,71 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file NavSatStatusCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUSCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUSCDRAUX_HPP_ + +#include "NavSatStatus.h" + +constexpr uint32_t sensor_msgs_msg_NavSatStatus_max_cdr_typesize {8UL}; +constexpr uint32_t sensor_msgs_msg_NavSatStatus_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::NavSatStatus& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUSCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusCdrAux.ipp new file mode 100644 index 00000000000..05609d1fa78 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusCdrAux.ipp @@ -0,0 +1,159 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file NavSatStatusCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUSCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUSCDRAUX_IPP_ + +#include "NavSatStatusCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const sensor_msgs::msg::NavSatStatus& data, + size_t& current_alignment) +{ + using namespace sensor_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.status(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.service(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::NavSatStatus& data) +{ + using namespace sensor_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.status() + << eprosima::fastcdr::MemberId(1) << data.service() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + sensor_msgs::msg::NavSatStatus& data) +{ + using namespace sensor_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.status(); + break; + + case 1: + dcdr >> data.service(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::NavSatStatus& data) +{ + using namespace sensor_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUSCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusPubSubTypes.cxx new file mode 100644 index 00000000000..2de2e0c5573 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusPubSubTypes.cxx @@ -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 NavSatStatusPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "NavSatStatusPubSubTypes.h" +#include "NavSatStatusCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace sensor_msgs { +namespace msg { +namespace NavSatStatus_Constants { + + + + + + + + + + + + + + + + + + + + + +} //End of namespace NavSatStatus_Constants + + + +NavSatStatusPubSubType::NavSatStatusPubSubType() +{ + setName("sensor_msgs::msg::dds_::NavSatStatus_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(NavSatStatus::getMaxCdrSerializedSize()); +#else + sensor_msgs_msg_NavSatStatus_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +NavSatStatusPubSubType::~NavSatStatusPubSubType() +{ +} + +bool NavSatStatusPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + NavSatStatus* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool NavSatStatusPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + NavSatStatus* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function NavSatStatusPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* NavSatStatusPubSubType::createData() +{ + return reinterpret_cast(new NavSatStatus()); +} + +void NavSatStatusPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool NavSatStatusPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace sensor_msgs + 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..1db7c63ca58 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/NavSatStatusPubSubTypes.h @@ -0,0 +1,157 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_NAVSATSTATUS_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "NavSatStatus.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { +namespace NavSatStatus_Constants { + + + + + + + + + + + + + + + + + + + + +} // namespace NavSatStatus_Constants + + + +/*! + * @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 ~NavSatStatusPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // 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.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2.cxx new file mode 100644 index 00000000000..e6120a30004 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2.cxx @@ -0,0 +1,433 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace sensor_msgs { + +namespace msg { + + + +PointCloud2::PointCloud2() +{ +} + +PointCloud2::~PointCloud2() +{ +} + +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; +} + +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; +} + +PointCloud2& 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; +} + +PointCloud2& 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 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 PointCloud2::operator !=( + const PointCloud2& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member header + * @param _header New value to be copied in member header + */ +void 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 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& PointCloud2::header() const +{ + return m_header; +} + +/*! + * @brief This function returns a reference to member header + * @return Reference to member header + */ +std_msgs::msg::Header& PointCloud2::header() +{ + return m_header; +} + + +/*! + * @brief This function sets a value in member height + * @param _height New value for member height + */ +void PointCloud2::height( + uint32_t _height) +{ + m_height = _height; +} + +/*! + * @brief This function returns the value of member height + * @return Value of member height + */ +uint32_t PointCloud2::height() const +{ + return m_height; +} + +/*! + * @brief This function returns a reference to member height + * @return Reference to member height + */ +uint32_t& PointCloud2::height() +{ + return m_height; +} + + +/*! + * @brief This function sets a value in member width + * @param _width New value for member width + */ +void PointCloud2::width( + uint32_t _width) +{ + m_width = _width; +} + +/*! + * @brief This function returns the value of member width + * @return Value of member width + */ +uint32_t PointCloud2::width() const +{ + return m_width; +} + +/*! + * @brief This function returns a reference to member width + * @return Reference to member width + */ +uint32_t& 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 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 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& PointCloud2::fields() const +{ + return m_fields; +} + +/*! + * @brief This function returns a reference to member fields + * @return Reference to member fields + */ +std::vector& 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 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 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& 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 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 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& 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 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 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& 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 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 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& PointCloud2::data() const +{ + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +std::vector& 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 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 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& PointCloud2::is_dense() +{ + return m_is_dense; +} + + + + +} // namespace msg + + +} // namespace sensor_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PointCloud2CdrAux.ipp" + 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..88e6da85ad5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2.h @@ -0,0 +1,360 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "std_msgs/msg/Header.h" +#include "PointField.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; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace sensor_msgs { + +namespace msg { + + + +/*! + * @brief This class represents the structure PointCloud2 defined by the user in the IDL file. + * @ingroup PointCloud2 + */ +class PointCloud2 +{ +public: + + /*! + * @brief Default constructor. + */ + eProsima_user_DllExport PointCloud2(); + + /*! + * @brief Default destructor. + */ + eProsima_user_DllExport ~PointCloud2(); + + /*! + * @brief Copy constructor. + * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. + */ + eProsima_user_DllExport PointCloud2( + const PointCloud2& x); + + /*! + * @brief Move constructor. + * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. + */ + eProsima_user_DllExport PointCloud2( + PointCloud2&& x) noexcept; + + /*! + * @brief Copy assignment. + * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. + */ + eProsima_user_DllExport PointCloud2& operator =( + const PointCloud2& x); + + /*! + * @brief Move assignment. + * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. + */ + eProsima_user_DllExport PointCloud2& operator =( + PointCloud2&& x) noexcept; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::PointCloud2 object to compare. + */ + eProsima_user_DllExport bool operator ==( + const PointCloud2& x) const; + + /*! + * @brief Comparison operator. + * @param x sensor_msgs::msg::PointCloud2 object to compare. + */ + eProsima_user_DllExport bool operator !=( + const PointCloud2& 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 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 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(); + +private: + + std_msgs::msg::Header m_header; + uint32_t m_height{0}; + uint32_t m_width{0}; + std::vector m_fields; + bool m_is_bigendian{false}; + uint32_t m_point_step{0}; + uint32_t m_row_step{0}; + std::vector m_data; + bool m_is_dense{false}; + +}; + +} // namespace msg + +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2CdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2CdrAux.hpp new file mode 100644 index 00000000000..495ba270564 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2CdrAux.hpp @@ -0,0 +1,51 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PointCloud2CdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2CDRAUX_HPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2CDRAUX_HPP_ + +#include "PointCloud2.h" + +constexpr uint32_t sensor_msgs_msg_PointCloud2_max_cdr_typesize {28013UL}; +constexpr uint32_t sensor_msgs_msg_PointCloud2_max_key_cdr_typesize {0UL}; + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::PointCloud2& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2CDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2CdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2CdrAux.ipp new file mode 100644 index 00000000000..4a1f5c11621 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2CdrAux.ipp @@ -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 PointCloud2CdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2CDRAUX_IPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2CDRAUX_IPP_ + +#include "PointCloud2CdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const sensor_msgs::msg::PointCloud2& data, + size_t& current_alignment) +{ + using namespace sensor_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.header(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.height(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.width(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.fields(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.is_bigendian(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(5), + data.point_step(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(6), + data.row_step(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(7), + data.data(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(8), + data.is_dense(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::PointCloud2& data) +{ + using namespace sensor_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.header() + << eprosima::fastcdr::MemberId(1) << data.height() + << eprosima::fastcdr::MemberId(2) << data.width() + << eprosima::fastcdr::MemberId(3) << data.fields() + << eprosima::fastcdr::MemberId(4) << data.is_bigendian() + << eprosima::fastcdr::MemberId(5) << data.point_step() + << eprosima::fastcdr::MemberId(6) << data.row_step() + << eprosima::fastcdr::MemberId(7) << data.data() + << eprosima::fastcdr::MemberId(8) << data.is_dense() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + sensor_msgs::msg::PointCloud2& data) +{ + using namespace sensor_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.header(); + break; + + case 1: + dcdr >> data.height(); + break; + + case 2: + dcdr >> data.width(); + break; + + case 3: + dcdr >> data.fields(); + break; + + case 4: + dcdr >> data.is_bigendian(); + break; + + case 5: + dcdr >> data.point_step(); + break; + + case 6: + dcdr >> data.row_step(); + break; + + case 7: + dcdr >> data.data(); + break; + + case 8: + dcdr >> data.is_dense(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::PointCloud2& data) +{ + using namespace sensor_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2CDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2PubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2PubSubTypes.cxx new file mode 100644 index 00000000000..20d26b966c7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2PubSubTypes.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 PointCloud2PubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PointCloud2PubSubTypes.h" +#include "PointCloud2CdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace sensor_msgs { +namespace msg { + + +PointCloud2PubSubType::PointCloud2PubSubType() +{ + setName("sensor_msgs::msg::dds_::PointCloud2_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PointCloud2::getMaxCdrSerializedSize()); +#else + sensor_msgs_msg_PointCloud2_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PointCloud2PubSubType::~PointCloud2PubSubType() +{ +} + +bool PointCloud2PubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + PointCloud2* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PointCloud2PubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + PointCloud2* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PointCloud2PubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* PointCloud2PubSubType::createData() +{ + return reinterpret_cast(new PointCloud2()); +} + +void PointCloud2PubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool PointCloud2PubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..35c4abe3427 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointCloud2PubSubTypes.h @@ -0,0 +1,137 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "PointCloud2.h" + +#include "std_msgs/msg/HeaderPubSubTypes.h" +#include "PointFieldPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 + */ +class PointCloud2PubSubType : public eprosima::fastdds::dds::TopicDataType +{ +public: + + typedef PointCloud2 type; + + eProsima_user_DllExport PointCloud2PubSubType(); + + eProsima_user_DllExport ~PointCloud2PubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointField.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointField.cxx new file mode 100644 index 00000000000..5c883168e00 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointField.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 PointField.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "PointField.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace sensor_msgs { + +namespace msg { + +namespace PointField_Constants { + + +} // namespace PointField_Constants + + +PointField::PointField() +{ +} + +PointField::~PointField() +{ +} + +PointField::PointField( + const PointField& x) +{ + m_name = x.m_name; + m_offset = x.m_offset; + m_datatype = x.m_datatype; + m_count = x.m_count; +} + +PointField::PointField( + PointField&& x) noexcept +{ + m_name = std::move(x.m_name); + m_offset = x.m_offset; + m_datatype = x.m_datatype; + m_count = x.m_count; +} + +PointField& PointField::operator =( + const PointField& x) +{ + + m_name = x.m_name; + m_offset = x.m_offset; + m_datatype = x.m_datatype; + m_count = x.m_count; + return *this; +} + +PointField& PointField::operator =( + PointField&& x) noexcept +{ + + m_name = std::move(x.m_name); + m_offset = x.m_offset; + m_datatype = x.m_datatype; + m_count = x.m_count; + return *this; +} + +bool PointField::operator ==( + const PointField& x) const +{ + return (m_name == x.m_name && + m_offset == x.m_offset && + m_datatype == x.m_datatype && + m_count == x.m_count); +} + +bool PointField::operator !=( + const PointField& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member name + * @param _name New value to be copied in member name + */ +void PointField::name( + const std::string& _name) +{ + m_name = _name; +} + +/*! + * @brief This function moves the value in member name + * @param _name New value to be moved in member name + */ +void PointField::name( + std::string&& _name) +{ + m_name = std::move(_name); +} + +/*! + * @brief This function returns a constant reference to member name + * @return Constant reference to member name + */ +const std::string& PointField::name() const +{ + return m_name; +} + +/*! + * @brief This function returns a reference to member name + * @return Reference to member name + */ +std::string& PointField::name() +{ + return m_name; +} + + +/*! + * @brief This function sets a value in member offset + * @param _offset New value for member offset + */ +void PointField::offset( + uint32_t _offset) +{ + m_offset = _offset; +} + +/*! + * @brief This function returns the value of member offset + * @return Value of member offset + */ +uint32_t PointField::offset() const +{ + return m_offset; +} + +/*! + * @brief This function returns a reference to member offset + * @return Reference to member offset + */ +uint32_t& PointField::offset() +{ + return m_offset; +} + + +/*! + * @brief This function sets a value in member datatype + * @param _datatype New value for member datatype + */ +void PointField::datatype( + uint8_t _datatype) +{ + m_datatype = _datatype; +} + +/*! + * @brief This function returns the value of member datatype + * @return Value of member datatype + */ +uint8_t PointField::datatype() const +{ + return m_datatype; +} + +/*! + * @brief This function returns a reference to member datatype + * @return Reference to member datatype + */ +uint8_t& PointField::datatype() +{ + return m_datatype; +} + + +/*! + * @brief This function sets a value in member count + * @param _count New value for member count + */ +void PointField::count( + uint32_t _count) +{ + m_count = _count; +} + +/*! + * @brief This function returns the value of member count + * @return Value of member count + */ +uint32_t PointField::count() const +{ + return m_count; +} + +/*! + * @brief This function returns a reference to member count + * @return Reference to member count + */ +uint32_t& PointField::count() +{ + return m_count; +} + + + + +} // namespace msg + + +} // namespace sensor_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "PointFieldCdrAux.ipp" + 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..ab0016a93d2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointField.h @@ -0,0 +1,251 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 +#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; +class CdrSizeCalculator; +} // namespace fastcdr +} // namespace eprosima + + + +namespace sensor_msgs { + +namespace msg { + +namespace PointField_Constants { + +const uint8_t INT8 = 1; +const uint8_t UINT8 = 2; +const uint8_t INT16 = 3; +const uint8_t UINT16 = 4; +const uint8_t INT32 = 5; +const uint8_t UINT32 = 6; +const uint8_t FLOAT32 = 7; +const uint8_t FLOAT64 = 8; + +} // namespace PointField_Constants + + +/*! + * @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(); + +private: + + std::string m_name; + uint32_t m_offset{0}; + uint8_t m_datatype{0}; + uint32_t m_count{0}; + +}; + +} // namespace msg + +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldCdrAux.hpp new file mode 100644 index 00000000000..6229c340619 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldCdrAux.hpp @@ -0,0 +1,67 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file PointFieldCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELDCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELDCDRAUX_HPP_ + +#include "PointField.h" + +constexpr uint32_t sensor_msgs_msg_PointField_max_cdr_typesize {276UL}; +constexpr uint32_t sensor_msgs_msg_PointField_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::PointField& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELDCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldCdrAux.ipp new file mode 100644 index 00000000000..76b7a500dad --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldCdrAux.ipp @@ -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 PointFieldCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELDCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELDCDRAUX_IPP_ + +#include "PointFieldCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const sensor_msgs::msg::PointField& data, + size_t& current_alignment) +{ + using namespace sensor_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.name(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.offset(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.datatype(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.count(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::PointField& data) +{ + using namespace sensor_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.name() + << eprosima::fastcdr::MemberId(1) << data.offset() + << eprosima::fastcdr::MemberId(2) << data.datatype() + << eprosima::fastcdr::MemberId(3) << data.count() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + sensor_msgs::msg::PointField& data) +{ + using namespace sensor_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.name(); + break; + + case 1: + dcdr >> data.offset(); + break; + + case 2: + dcdr >> data.datatype(); + break; + + case 3: + dcdr >> data.count(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::PointField& data) +{ + using namespace sensor_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELDCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldPubSubTypes.cxx new file mode 100644 index 00000000000..b3bf4e9473d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldPubSubTypes.cxx @@ -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 PointFieldPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "PointFieldPubSubTypes.h" +#include "PointFieldCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace sensor_msgs { +namespace msg { +namespace PointField_Constants { + + + + + + + + + + + + + + + + + +} //End of namespace PointField_Constants + + + +PointFieldPubSubType::PointFieldPubSubType() +{ + setName("sensor_msgs::msg::dds_::PointField_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(PointField::getMaxCdrSerializedSize()); +#else + sensor_msgs_msg_PointField_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +PointFieldPubSubType::~PointFieldPubSubType() +{ +} + +bool PointFieldPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + PointField* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool PointFieldPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + PointField* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function PointFieldPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* PointFieldPubSubType::createData() +{ + return reinterpret_cast(new PointField()); +} + +void PointFieldPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool PointFieldPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace sensor_msgs + 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..e1a56d6749e --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/PointFieldPubSubTypes.h @@ -0,0 +1,153 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "PointField.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { +namespace PointField_Constants { + + + + + + + + + + + + + + + + +} // namespace PointField_Constants + + + +/*! + * @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 ~PointFieldPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterest.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterest.cxx new file mode 100644 index 00000000000..20f024b0526 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterest.cxx @@ -0,0 +1,267 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "RegionOfInterest.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace sensor_msgs { + +namespace msg { + + + +RegionOfInterest::RegionOfInterest() +{ +} + +RegionOfInterest::~RegionOfInterest() +{ +} + +RegionOfInterest::RegionOfInterest( + const RegionOfInterest& x) +{ + m_x_offset = x.m_x_offset; + m_y_offset = x.m_y_offset; + m_height = x.m_height; + m_width = x.m_width; + m_do_rectify = x.m_do_rectify; +} + +RegionOfInterest::RegionOfInterest( + RegionOfInterest&& x) noexcept +{ + m_x_offset = x.m_x_offset; + m_y_offset = x.m_y_offset; + m_height = x.m_height; + m_width = x.m_width; + m_do_rectify = x.m_do_rectify; +} + +RegionOfInterest& RegionOfInterest::operator =( + const RegionOfInterest& x) +{ + + m_x_offset = x.m_x_offset; + m_y_offset = x.m_y_offset; + m_height = x.m_height; + m_width = x.m_width; + m_do_rectify = x.m_do_rectify; + return *this; +} + +RegionOfInterest& RegionOfInterest::operator =( + RegionOfInterest&& x) noexcept +{ + + m_x_offset = x.m_x_offset; + m_y_offset = x.m_y_offset; + m_height = x.m_height; + m_width = x.m_width; + m_do_rectify = x.m_do_rectify; + return *this; +} + +bool RegionOfInterest::operator ==( + const RegionOfInterest& x) const +{ + return (m_x_offset == x.m_x_offset && + m_y_offset == x.m_y_offset && + m_height == x.m_height && + m_width == x.m_width && + m_do_rectify == x.m_do_rectify); +} + +bool RegionOfInterest::operator !=( + const RegionOfInterest& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member x_offset + * @param _x_offset New value for member x_offset + */ +void RegionOfInterest::x_offset( + uint32_t _x_offset) +{ + m_x_offset = _x_offset; +} + +/*! + * @brief This function returns the value of member x_offset + * @return Value of member x_offset + */ +uint32_t RegionOfInterest::x_offset() const +{ + return m_x_offset; +} + +/*! + * @brief This function returns a reference to member x_offset + * @return Reference to member x_offset + */ +uint32_t& RegionOfInterest::x_offset() +{ + return m_x_offset; +} + + +/*! + * @brief This function sets a value in member y_offset + * @param _y_offset New value for member y_offset + */ +void RegionOfInterest::y_offset( + uint32_t _y_offset) +{ + m_y_offset = _y_offset; +} + +/*! + * @brief This function returns the value of member y_offset + * @return Value of member y_offset + */ +uint32_t RegionOfInterest::y_offset() const +{ + return m_y_offset; +} + +/*! + * @brief This function returns a reference to member y_offset + * @return Reference to member y_offset + */ +uint32_t& RegionOfInterest::y_offset() +{ + return m_y_offset; +} + + +/*! + * @brief This function sets a value in member height + * @param _height New value for member height + */ +void RegionOfInterest::height( + uint32_t _height) +{ + m_height = _height; +} + +/*! + * @brief This function returns the value of member height + * @return Value of member height + */ +uint32_t RegionOfInterest::height() const +{ + return m_height; +} + +/*! + * @brief This function returns a reference to member height + * @return Reference to member height + */ +uint32_t& RegionOfInterest::height() +{ + return m_height; +} + + +/*! + * @brief This function sets a value in member width + * @param _width New value for member width + */ +void RegionOfInterest::width( + uint32_t _width) +{ + m_width = _width; +} + +/*! + * @brief This function returns the value of member width + * @return Value of member width + */ +uint32_t RegionOfInterest::width() const +{ + return m_width; +} + +/*! + * @brief This function returns a reference to member width + * @return Reference to member width + */ +uint32_t& RegionOfInterest::width() +{ + return m_width; +} + + +/*! + * @brief This function sets a value in member do_rectify + * @param _do_rectify New value for member do_rectify + */ +void RegionOfInterest::do_rectify( + bool _do_rectify) +{ + m_do_rectify = _do_rectify; +} + +/*! + * @brief This function returns the value of member do_rectify + * @return Value of member do_rectify + */ +bool RegionOfInterest::do_rectify() const +{ + return m_do_rectify; +} + +/*! + * @brief This function returns a reference to member do_rectify + * @return Reference to member do_rectify + */ +bool& RegionOfInterest::do_rectify() +{ + return m_do_rectify; +} + + + + +} // namespace msg + + +} // namespace sensor_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "RegionOfInterestCdrAux.ipp" + 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..fc195e5bfc7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterest.h @@ -0,0 +1,253 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 +#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; +class CdrSizeCalculator; +} // 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(); + +private: + + uint32_t m_x_offset{0}; + uint32_t m_y_offset{0}; + uint32_t m_height{0}; + uint32_t m_width{0}; + bool m_do_rectify{false}; + +}; + +} // namespace msg + +} // namespace sensor_msgs + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestCdrAux.hpp new file mode 100644 index 00000000000..c754835efd5 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file RegionOfInterestCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTERESTCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTERESTCDRAUX_HPP_ + +#include "RegionOfInterest.h" + +constexpr uint32_t sensor_msgs_msg_RegionOfInterest_max_cdr_typesize {21UL}; +constexpr uint32_t sensor_msgs_msg_RegionOfInterest_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::RegionOfInterest& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTERESTCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestCdrAux.ipp new file mode 100644 index 00000000000..c59e7fe543d --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestCdrAux.ipp @@ -0,0 +1,162 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file RegionOfInterestCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTERESTCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTERESTCDRAUX_IPP_ + +#include "RegionOfInterestCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const sensor_msgs::msg::RegionOfInterest& data, + size_t& current_alignment) +{ + using namespace sensor_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.x_offset(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.y_offset(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.height(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(3), + data.width(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(4), + data.do_rectify(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::RegionOfInterest& data) +{ + using namespace sensor_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.x_offset() + << eprosima::fastcdr::MemberId(1) << data.y_offset() + << eprosima::fastcdr::MemberId(2) << data.height() + << eprosima::fastcdr::MemberId(3) << data.width() + << eprosima::fastcdr::MemberId(4) << data.do_rectify() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + sensor_msgs::msg::RegionOfInterest& data) +{ + using namespace sensor_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.x_offset(); + break; + + case 1: + dcdr >> data.y_offset(); + break; + + case 2: + dcdr >> data.height(); + break; + + case 3: + dcdr >> data.width(); + break; + + case 4: + dcdr >> data.do_rectify(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const sensor_msgs::msg::RegionOfInterest& data) +{ + using namespace sensor_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTERESTCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestPubSubTypes.cxx new file mode 100644 index 00000000000..f47cad115d0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestPubSubTypes.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 RegionOfInterestPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "RegionOfInterestPubSubTypes.h" +#include "RegionOfInterestCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace sensor_msgs { +namespace msg { + + +RegionOfInterestPubSubType::RegionOfInterestPubSubType() +{ + setName("sensor_msgs::msg::dds_::RegionOfInterest_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(RegionOfInterest::getMaxCdrSerializedSize()); +#else + sensor_msgs_msg_RegionOfInterest_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +RegionOfInterestPubSubType::~RegionOfInterestPubSubType() +{ +} + +bool RegionOfInterestPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + RegionOfInterest* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool RegionOfInterestPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + RegionOfInterest* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function RegionOfInterestPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* RegionOfInterestPubSubType::createData() +{ + return reinterpret_cast(new RegionOfInterest()); +} + +void RegionOfInterestPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool RegionOfInterestPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace sensor_msgs + 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..017cc414279 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/sensor_msgs/msg/RegionOfInterestPubSubTypes.h @@ -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 RegionOfInterestPubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_REGIONOFINTEREST_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "RegionOfInterest.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + +/*! + * @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 ~RegionOfInterestPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // 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..557d67da896 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitive.cxx @@ -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 SolidPrimitive.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#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 + + +namespace shape_msgs { + +namespace msg { + +namespace SolidPrimitive_Constants { + + +} // namespace SolidPrimitive_Constants + + +SolidPrimitive::SolidPrimitive() +{ +} + +SolidPrimitive::~SolidPrimitive() +{ +} + +SolidPrimitive::SolidPrimitive( + const SolidPrimitive& x) +{ + m_type = x.m_type; + m_dimensions = x.m_dimensions; + m_polygon = x.m_polygon; +} + +SolidPrimitive::SolidPrimitive( + SolidPrimitive&& x) noexcept +{ + m_type = x.m_type; + m_dimensions = std::move(x.m_dimensions); + m_polygon = std::move(x.m_polygon); +} + +SolidPrimitive& SolidPrimitive::operator =( + const SolidPrimitive& x) +{ + + m_type = x.m_type; + m_dimensions = x.m_dimensions; + m_polygon = x.m_polygon; + return *this; +} + +SolidPrimitive& SolidPrimitive::operator =( + SolidPrimitive&& x) noexcept +{ + + m_type = x.m_type; + m_dimensions = std::move(x.m_dimensions); + m_polygon = std::move(x.m_polygon); + return *this; +} + +bool SolidPrimitive::operator ==( + const SolidPrimitive& x) const +{ + return (m_type == x.m_type && + m_dimensions == x.m_dimensions && + m_polygon == x.m_polygon); +} + +bool SolidPrimitive::operator !=( + const SolidPrimitive& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member type + * @param _type New value for member type + */ +void SolidPrimitive::type( + uint8_t _type) +{ + m_type = _type; +} + +/*! + * @brief This function returns the value of member type + * @return Value of member type + */ +uint8_t SolidPrimitive::type() const +{ + return m_type; +} + +/*! + * @brief This function returns a reference to member type + * @return Reference to member type + */ +uint8_t& 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 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 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& SolidPrimitive::dimensions() const +{ + return m_dimensions; +} + +/*! + * @brief This function returns a reference to member dimensions + * @return Reference to member dimensions + */ +std::vector& 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 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 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& SolidPrimitive::polygon() const +{ + return m_polygon; +} + +/*! + * @brief This function returns a reference to member polygon + * @return Reference to member polygon + */ +geometry_msgs::msg::Polygon& SolidPrimitive::polygon() +{ + return m_polygon; +} + + + + +} // namespace msg + + +} // namespace shape_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "SolidPrimitiveCdrAux.ipp" + 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..e47708f90b6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitive.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 SolidPrimitive.h + * This header file contains the declaration of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_H_ +#define _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "geometry_msgs/msg/Polygon.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +private: + + uint8_t m_type{0}; + std::vector m_dimensions; + geometry_msgs::msg::Polygon m_polygon; + +}; + +} // namespace msg + +} // namespace shape_msgs + +#endif // _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitiveCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitiveCdrAux.hpp new file mode 100644 index 00000000000..87ea222fa32 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitiveCdrAux.hpp @@ -0,0 +1,79 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SolidPrimitiveCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVECDRAUX_HPP_ + +#include "SolidPrimitive.h" + +constexpr uint32_t shape_msgs_msg_SolidPrimitive_max_cdr_typesize {1652UL}; +constexpr uint32_t shape_msgs_msg_SolidPrimitive_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const shape_msgs::msg::SolidPrimitive& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitiveCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitiveCdrAux.ipp new file mode 100644 index 00000000000..cc661f348b0 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitiveCdrAux.ipp @@ -0,0 +1,175 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file SolidPrimitiveCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVECDRAUX_IPP_ + +#include "SolidPrimitiveCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const shape_msgs::msg::SolidPrimitive& data, + size_t& current_alignment) +{ + using namespace shape_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.type(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.dimensions(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(2), + data.polygon(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const shape_msgs::msg::SolidPrimitive& data) +{ + using namespace shape_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.type() + << eprosima::fastcdr::MemberId(1) << data.dimensions() + << eprosima::fastcdr::MemberId(2) << data.polygon() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + shape_msgs::msg::SolidPrimitive& data) +{ + using namespace shape_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.type(); + break; + + case 1: + dcdr >> data.dimensions(); + break; + + case 2: + dcdr >> data.polygon(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const shape_msgs::msg::SolidPrimitive& data) +{ + using namespace shape_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVECDRAUX_IPP_ + 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..51eeda1f9ed --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitivePubSubTypes.cxx @@ -0,0 +1,230 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "SolidPrimitivePubSubTypes.h" +#include "SolidPrimitiveCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace shape_msgs { +namespace msg { +namespace SolidPrimitive_Constants { + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} //End of namespace SolidPrimitive_Constants + + + +SolidPrimitivePubSubType::SolidPrimitivePubSubType() +{ + setName("shape_msgs::msg::dds_::SolidPrimitive_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(SolidPrimitive::getMaxCdrSerializedSize()); +#else + shape_msgs_msg_SolidPrimitive_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +SolidPrimitivePubSubType::~SolidPrimitivePubSubType() +{ +} + +bool SolidPrimitivePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool SolidPrimitivePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function SolidPrimitivePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +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) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..110ddcad3c7 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/shape_msgs/msg/SolidPrimitivePubSubTypes.h @@ -0,0 +1,166 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "SolidPrimitive.h" + +#include "geometry_msgs/msg/PolygonPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + + + + + + + + + + + + + + + + + + + + + + + + + + +} // 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 ~SolidPrimitivePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace shape_msgs + +#endif // _FAST_DDS_GENERATED_SHAPE_MSGS_MSG_SOLIDPRIMITIVE_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32.cxx b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32.cxx new file mode 100644 index 00000000000..bca4f25edfa --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32.cxx @@ -0,0 +1,131 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Float32.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace std_msgs { + +namespace msg { + + + +Float32::Float32() +{ +} + +Float32::~Float32() +{ +} + +Float32::Float32( + const Float32& x) +{ + m_data = x.m_data; +} + +Float32::Float32( + Float32&& x) noexcept +{ + m_data = x.m_data; +} + +Float32& Float32::operator =( + const Float32& x) +{ + + m_data = x.m_data; + return *this; +} + +Float32& Float32::operator =( + Float32&& x) noexcept +{ + + m_data = x.m_data; + return *this; +} + +bool Float32::operator ==( + const Float32& x) const +{ + return (m_data == x.m_data); +} + +bool Float32::operator !=( + const Float32& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function sets a value in member data + * @param _data New value for member data + */ +void Float32::data( + float _data) +{ + m_data = _data; +} + +/*! + * @brief This function returns the value of member data + * @return Value of member data + */ +float Float32::data() const +{ + return m_data; +} + +/*! + * @brief This function returns a reference to member data + * @return Reference to member data + */ +float& Float32::data() +{ + return m_data; +} + + + + +} // namespace msg + + +} // namespace std_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "Float32CdrAux.ipp" + 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..0fec91c0220 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32.h @@ -0,0 +1,169 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#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 +#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; +class CdrSizeCalculator; +} // 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(); + +private: + + float m_data{0.0}; + +}; + +} // namespace msg + +} // namespace std_msgs + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_H_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32CdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32CdrAux.hpp new file mode 100644 index 00000000000..cec1bb34113 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32CdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file Float32CdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32CDRAUX_HPP_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32CDRAUX_HPP_ + +#include "Float32.h" + +constexpr uint32_t std_msgs_msg_Float32_max_cdr_typesize {8UL}; +constexpr uint32_t std_msgs_msg_Float32_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const std_msgs::msg::Float32& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32CDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32CdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32CdrAux.ipp new file mode 100644 index 00000000000..8f8c778d236 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32CdrAux.ipp @@ -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 Float32CdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32CDRAUX_IPP_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32CDRAUX_IPP_ + +#include "Float32CdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const std_msgs::msg::Float32& data, + size_t& current_alignment) +{ + using namespace std_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.data(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const std_msgs::msg::Float32& data) +{ + using namespace std_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.data() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + std_msgs::msg::Float32& data) +{ + using namespace std_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.data(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const std_msgs::msg::Float32& data) +{ + using namespace std_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32CDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32PubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32PubSubTypes.cxx new file mode 100644 index 00000000000..a4fe5cada35 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32PubSubTypes.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 Float32PubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "Float32PubSubTypes.h" +#include "Float32CdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace std_msgs { +namespace msg { + + +Float32PubSubType::Float32PubSubType() +{ + setName("std_msgs::msg::dds_::Float32_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Float32::getMaxCdrSerializedSize()); +#else + std_msgs_msg_Float32_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +Float32PubSubType::~Float32PubSubType() +{ +} + +bool Float32PubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Float32* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool Float32PubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + Float32* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function Float32PubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* Float32PubSubType::createData() +{ + return reinterpret_cast(new Float32()); +} + +void Float32PubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool Float32PubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace std_msgs + 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..6e95c734831 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Float32PubSubTypes.h @@ -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 Float32PubSubTypes.h + * This header file contains the declaration of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Float32.h" + + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 { + + + +/*! + * @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 ~Float32PubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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 false; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace std_msgs + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_FLOAT32_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Header.cxx b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Header.cxx new file mode 100644 index 00000000000..7325e497331 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Header.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 Header.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "Header.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace std_msgs { + +namespace msg { + + + +Header::Header() +{ +} + +Header::~Header() +{ +} + +Header::Header( + const Header& x) +{ + m_stamp = x.m_stamp; + m_frame_id = x.m_frame_id; +} + +Header::Header( + Header&& x) noexcept +{ + m_stamp = std::move(x.m_stamp); + m_frame_id = std::move(x.m_frame_id); +} + +Header& Header::operator =( + const Header& x) +{ + + m_stamp = x.m_stamp; + m_frame_id = x.m_frame_id; + return *this; +} + +Header& Header::operator =( + Header&& x) noexcept +{ + + m_stamp = std::move(x.m_stamp); + m_frame_id = std::move(x.m_frame_id); + return *this; +} + +bool Header::operator ==( + const Header& x) const +{ + return (m_stamp == x.m_stamp && + m_frame_id == x.m_frame_id); +} + +bool Header::operator !=( + const Header& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member stamp + * @param _stamp New value to be copied in member stamp + */ +void Header::stamp( + const builtin_interfaces::msg::Time& _stamp) +{ + m_stamp = _stamp; +} + +/*! + * @brief This function moves the value in member stamp + * @param _stamp New value to be moved in member stamp + */ +void Header::stamp( + builtin_interfaces::msg::Time&& _stamp) +{ + m_stamp = std::move(_stamp); +} + +/*! + * @brief This function returns a constant reference to member stamp + * @return Constant reference to member stamp + */ +const builtin_interfaces::msg::Time& Header::stamp() const +{ + return m_stamp; +} + +/*! + * @brief This function returns a reference to member stamp + * @return Reference to member stamp + */ +builtin_interfaces::msg::Time& Header::stamp() +{ + return m_stamp; +} + + +/*! + * @brief This function copies the value in member frame_id + * @param _frame_id New value to be copied in member frame_id + */ +void Header::frame_id( + const std::string& _frame_id) +{ + m_frame_id = _frame_id; +} + +/*! + * @brief This function moves the value in member frame_id + * @param _frame_id New value to be moved in member frame_id + */ +void Header::frame_id( + std::string&& _frame_id) +{ + m_frame_id = std::move(_frame_id); +} + +/*! + * @brief This function returns a constant reference to member frame_id + * @return Constant reference to member frame_id + */ +const std::string& Header::frame_id() const +{ + return m_frame_id; +} + +/*! + * @brief This function returns a reference to member frame_id + * @return Reference to member frame_id + */ +std::string& Header::frame_id() +{ + return m_frame_id; +} + + + + +} // namespace msg + + +} // namespace std_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "HeaderCdrAux.ipp" + 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..7830600a303 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/Header.h @@ -0,0 +1,205 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_H_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "builtin_interfaces/msg/Time.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(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; +class CdrSizeCalculator; +} // 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) noexcept; + + /*! + * @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) noexcept; + + /*! + * @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(); + +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_ + + + diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderCdrAux.hpp new file mode 100644 index 00000000000..b1454ed55bf --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderCdrAux.hpp @@ -0,0 +1,50 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HeaderCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADERCDRAUX_HPP_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADERCDRAUX_HPP_ + +#include "Header.h" + +constexpr uint32_t std_msgs_msg_Header_max_cdr_typesize {276UL}; +constexpr uint32_t std_msgs_msg_Header_max_key_cdr_typesize {0UL}; + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const std_msgs::msg::Header& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADERCDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderCdrAux.ipp new file mode 100644 index 00000000000..87637400c62 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderCdrAux.ipp @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file HeaderCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADERCDRAUX_IPP_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADERCDRAUX_IPP_ + +#include "HeaderCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const std_msgs::msg::Header& data, + size_t& current_alignment) +{ + using namespace std_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.stamp(), current_alignment); + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(1), + data.frame_id(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const std_msgs::msg::Header& data) +{ + using namespace std_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.stamp() + << eprosima::fastcdr::MemberId(1) << data.frame_id() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + std_msgs::msg::Header& data) +{ + using namespace std_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.stamp(); + break; + + case 1: + dcdr >> data.frame_id(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const std_msgs::msg::Header& data) +{ + using namespace std_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADERCDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderPubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderPubSubTypes.cxx new file mode 100644 index 00000000000..1df295aadc6 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderPubSubTypes.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 HeaderPubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "HeaderPubSubTypes.h" +#include "HeaderCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace std_msgs { +namespace msg { + + +HeaderPubSubType::HeaderPubSubType() +{ + setName("std_msgs::msg::dds_::Header_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(Header::getMaxCdrSerializedSize()); +#else + std_msgs_msg_Header_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +HeaderPubSubType::~HeaderPubSubType() +{ +} + +bool HeaderPubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + Header* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool HeaderPubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + Header* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function HeaderPubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* HeaderPubSubType::createData() +{ + return reinterpret_cast(new Header()); +} + +void HeaderPubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool HeaderPubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //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..8fc3519cdd2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/std_msgs/msg/HeaderPubSubTypes.h @@ -0,0 +1,136 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "Header.h" + +#include "builtin_interfaces/msg/TimePubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~HeaderPubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // namespace msg +} // namespace std_msgs + +#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_PUBSUBTYPES_H_ + diff --git a/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessage.cxx b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessage.cxx new file mode 100644 index 00000000000..af688a9d630 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessage.cxx @@ -0,0 +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 TFMessage.cpp + * This source file contains the implementation of the described types in the IDL file. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifdef _WIN32 +// Remove linker warning LNK4221 on Visual Studio +namespace { +char dummy; +} // namespace +#endif // _WIN32 + +#include "TFMessage.h" + +#include + + +#include +using namespace eprosima::fastcdr::exception; + +#include + + +namespace tf2_msgs { + +namespace msg { + + + + + +TFMessage::TFMessage() +{ +} + +TFMessage::~TFMessage() +{ +} + +TFMessage::TFMessage( + const TFMessage& x) +{ + m_transforms = x.m_transforms; +} + +TFMessage::TFMessage( + TFMessage&& x) noexcept +{ + m_transforms = std::move(x.m_transforms); +} + +TFMessage& TFMessage::operator =( + const TFMessage& x) +{ + + m_transforms = x.m_transforms; + return *this; +} + +TFMessage& TFMessage::operator =( + TFMessage&& x) noexcept +{ + + m_transforms = std::move(x.m_transforms); + return *this; +} + +bool TFMessage::operator ==( + const TFMessage& x) const +{ + return (m_transforms == x.m_transforms); +} + +bool TFMessage::operator !=( + const TFMessage& x) const +{ + return !(*this == x); +} + +/*! + * @brief This function copies the value in member transforms + * @param _transforms New value to be copied in member transforms + */ +void TFMessage::transforms( + const std::vector& _transforms) +{ + m_transforms = _transforms; +} + +/*! + * @brief This function moves the value in member transforms + * @param _transforms New value to be moved in member transforms + */ +void TFMessage::transforms( + std::vector&& _transforms) +{ + m_transforms = std::move(_transforms); +} + +/*! + * @brief This function returns a constant reference to member transforms + * @return Constant reference to member transforms + */ +const std::vector& TFMessage::transforms() const +{ + return m_transforms; +} + +/*! + * @brief This function returns a reference to member transforms + * @return Reference to member transforms + */ +std::vector& TFMessage::transforms() +{ + return m_transforms; +} + + + + +} // namespace msg + + +} // namespace tf2_msgs +// Include auxiliary functions like for serializing/deserializing. +#include "TFMessageCdrAux.ipp" + 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..b0164a0c720 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessage.h @@ -0,0 +1,179 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_H_ +#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "geometry_msgs/msg/TransformStamped.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(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; +class CdrSizeCalculator; +} // 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(); + +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/fastdds/tf2_msgs/msg/TFMessageCdrAux.hpp b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessageCdrAux.hpp new file mode 100644 index 00000000000..37cb626dc86 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessageCdrAux.hpp @@ -0,0 +1,55 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TFMessageCdrAux.hpp + * This source file contains some definitions of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGECDRAUX_HPP_ +#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGECDRAUX_HPP_ + +#include "TFMessage.h" + +constexpr uint32_t tf2_msgs_msg_TFMessage_max_cdr_typesize {61608UL}; +constexpr uint32_t tf2_msgs_msg_TFMessage_max_key_cdr_typesize {0UL}; + + + + + +namespace eprosima { +namespace fastcdr { + +class Cdr; +class CdrSizeCalculator; + + + + + +eProsima_user_DllExport void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const tf2_msgs::msg::TFMessage& data); + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGECDRAUX_HPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessageCdrAux.ipp b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessageCdrAux.ipp new file mode 100644 index 00000000000..ee7632e2957 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessageCdrAux.ipp @@ -0,0 +1,132 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/*! + * @file TFMessageCdrAux.ipp + * This source file contains some declarations of CDR related functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + +#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGECDRAUX_IPP_ +#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGECDRAUX_IPP_ + +#include "TFMessageCdrAux.hpp" + +#include +#include + + +#include +using namespace eprosima::fastcdr::exception; + +namespace eprosima { +namespace fastcdr { + + + + + +template<> +eProsima_user_DllExport size_t calculate_serialized_size( + eprosima::fastcdr::CdrSizeCalculator& calculator, + const tf2_msgs::msg::TFMessage& data, + size_t& current_alignment) +{ + using namespace tf2_msgs::msg; + + static_cast(data); + + eprosima::fastcdr::EncodingAlgorithmFlag previous_encoding = calculator.get_encoding(); + size_t calculated_size {calculator.begin_calculate_type_serialized_size( + eprosima::fastcdr::CdrVersion::XCDRv2 == calculator.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + current_alignment)}; + + + calculated_size += calculator.calculate_member_serialized_size(eprosima::fastcdr::MemberId(0), + data.transforms(), current_alignment); + + + calculated_size += calculator.end_calculate_type_serialized_size(previous_encoding, current_alignment); + + return calculated_size; +} + +template<> +eProsima_user_DllExport void serialize( + eprosima::fastcdr::Cdr& scdr, + const tf2_msgs::msg::TFMessage& data) +{ + using namespace tf2_msgs::msg; + + eprosima::fastcdr::Cdr::state current_state(scdr); + scdr.begin_serialize_type(current_state, + eprosima::fastcdr::CdrVersion::XCDRv2 == scdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR); + + scdr + << eprosima::fastcdr::MemberId(0) << data.transforms() +; + scdr.end_serialize_type(current_state); +} + +template<> +eProsima_user_DllExport void deserialize( + eprosima::fastcdr::Cdr& cdr, + tf2_msgs::msg::TFMessage& data) +{ + using namespace tf2_msgs::msg; + + cdr.deserialize_type(eprosima::fastcdr::CdrVersion::XCDRv2 == cdr.get_cdr_version() ? + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2 : + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR, + [&data](eprosima::fastcdr::Cdr& dcdr, const eprosima::fastcdr::MemberId& mid) -> bool + { + bool ret_value = true; + switch (mid.id) + { + case 0: + dcdr >> data.transforms(); + break; + + default: + ret_value = false; + break; + } + return ret_value; + }); +} + +void serialize_key( + eprosima::fastcdr::Cdr& scdr, + const tf2_msgs::msg::TFMessage& data) +{ + using namespace tf2_msgs::msg; + + static_cast(scdr); + static_cast(data); +} + + + + + +} // namespace fastcdr +} // namespace eprosima + +#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGECDRAUX_IPP_ + diff --git a/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessagePubSubTypes.cxx b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessagePubSubTypes.cxx new file mode 100644 index 00000000000..b0f08b3f429 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessagePubSubTypes.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 TFMessagePubSubTypes.cpp + * This header file contains the implementation of the serialization functions. + * + * This file was generated by the tool fastddsgen (version: 3.3.2). + */ + + +#include +#include + +#include + +#include "TFMessagePubSubTypes.h" +#include "TFMessageCdrAux.hpp" + +using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; +using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; +using DataRepresentationId_t = eprosima::fastdds::dds::DataRepresentationId_t; + +namespace tf2_msgs { +namespace msg { + + + + +TFMessagePubSubType::TFMessagePubSubType() +{ + setName("tf2_msgs::msg::dds_::TFMessage_"); + uint32_t type_size = +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(TFMessage::getMaxCdrSerializedSize()); +#else + tf2_msgs_msg_TFMessage_max_cdr_typesize; +#endif + type_size += static_cast(eprosima::fastcdr::Cdr::alignment(type_size, 4)); /* possible submessage alignment */ + m_typeSize = type_size + 4; /*encapsulation*/ + m_isGetKeyDefined = false; +} + +TFMessagePubSubType::~TFMessagePubSubType() +{ +} + +bool TFMessagePubSubType::serialize( + void* data, + SerializedPayload_t* payload, + DataRepresentationId_t data_representation) +{ + TFMessage* 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, + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 : eprosima::fastcdr::CdrVersion::XCDRv2); + payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_encoding_flag( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::EncodingAlgorithmFlag::PLAIN_CDR : + eprosima::fastcdr::EncodingAlgorithmFlag::DELIMIT_CDR2); +#endif // FASTCDR_VERSION_MAJOR > 1 + + try + { + // Serialize encapsulation + ser.serialize_encapsulation(); + // Serialize the object. + ser << *p_type; +#if FASTCDR_VERSION_MAJOR > 1 + ser.set_dds_cdr_options({0, 0}); +#else + ser.setDDSCdrOptions(0); +#endif // FASTCDR_VERSION_MAJOR > 1 + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + // Get the serialized length +#if FASTCDR_VERSION_MAJOR == 1 + payload->length = static_cast(ser.getSerializedDataLength()); +#else + payload->length = static_cast(ser.get_serialized_data_length()); +#endif // FASTCDR_VERSION_MAJOR == 1 + return true; +} + +bool TFMessagePubSubType::deserialize( + SerializedPayload_t* payload, + void* data) +{ + try + { + // Convert DATA to pointer of your type + TFMessage* 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 +#if FASTCDR_VERSION_MAJOR == 1 + , eprosima::fastcdr::Cdr::CdrType::DDS_CDR +#endif // FASTCDR_VERSION_MAJOR == 1 + ); + + // Deserialize encapsulation. + deser.read_encapsulation(); + payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE; + + // Deserialize the object. + deser >> *p_type; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return false; + } + + return true; +} + +std::function TFMessagePubSubType::getSerializedSizeProvider( + void* data, + DataRepresentationId_t data_representation) +{ + return [data, data_representation]() -> uint32_t + { +#if FASTCDR_VERSION_MAJOR == 1 + static_cast(data_representation); + return static_cast(type::getCdrSerializedSize(*static_cast(data))) + + 4u /*encapsulation*/; +#else + try + { + eprosima::fastcdr::CdrSizeCalculator calculator( + data_representation == DataRepresentationId_t::XCDR_DATA_REPRESENTATION ? + eprosima::fastcdr::CdrVersion::XCDRv1 :eprosima::fastcdr::CdrVersion::XCDRv2); + size_t current_alignment {0}; + return static_cast(calculator.calculate_serialized_size( + *static_cast(data), current_alignment)) + + 4u /*encapsulation*/; + } + catch (eprosima::fastcdr::exception::Exception& /*exception*/) + { + return 0; + } +#endif // FASTCDR_VERSION_MAJOR == 1 + }; +} + +void* TFMessagePubSubType::createData() +{ + return reinterpret_cast(new TFMessage()); +} + +void TFMessagePubSubType::deleteData( + void* data) +{ + delete(reinterpret_cast(data)); +} + +bool TFMessagePubSubType::getKey( + void* data, + InstanceHandle_t* handle, + bool force_md5) +{ + static_cast(data); + static_cast(handle); + static_cast(force_md5); + + return false; +} + + + +} //End of namespace msg + + +} //End of namespace tf2_msgs + 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..b956035b2b2 --- /dev/null +++ b/LibCarla/source/carla/ros2/fastdds/tf2_msgs/msg/TFMessagePubSubTypes.h @@ -0,0 +1,138 @@ +// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES 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 fastddsgen (version: 3.3.2). + */ + + +#ifndef _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_PUBSUBTYPES_H_ +#define _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_PUBSUBTYPES_H_ + +#include + +#include +#include +#include +#include +#include + +#include "TFMessage.h" + +#include "geometry_msgs/msg/TransformStampedPubSubTypes.h" + +#if !defined(GEN_API_VER) || (GEN_API_VER != 2) +#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 ~TFMessagePubSubType() override; + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload) override + { + return serialize(data, payload, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport bool serialize( + void* data, + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool deserialize( + eprosima::fastrtps::rtps::SerializedPayload_t* payload, + void* data) override; + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data) override + { + return getSerializedSizeProvider(data, eprosima::fastdds::dds::DEFAULT_DATA_REPRESENTATION); + } + + eProsima_user_DllExport std::function getSerializedSizeProvider( + void* data, + eprosima::fastdds::dds::DataRepresentationId_t data_representation) override; + + eProsima_user_DllExport bool getKey( + void* data, + eprosima::fastrtps::rtps::InstanceHandle_t* ihandle, + bool force_md5 = false) override; + + eProsima_user_DllExport void* createData() override; + + eProsima_user_DllExport 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; + } + + eProsima_user_DllExport inline bool is_plain( + eprosima::fastdds::dds::DataRepresentationId_t data_representation) const override + { + static_cast(data_representation); + 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 + { + static_cast(memory); + return false; + } + +#endif // TOPIC_DATA_TYPE_API_HAS_CONSTRUCT_SAMPLE + +}; +} // 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 b5bb2c2faf7..00000000000 --- a/LibCarla/source/carla/ros2/publishers/BasePublisher.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 - -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) {} - - virtual ~BasePublisher() = default; - - std::string GetBaseTopicName() { return _base_topic_name; } - std::string GetFrameId() { return _frame_id; } - - virtual bool Publish() = 0; - - void* GetActor() { return _actor; } - - protected: - void* _actor { nullptr }; - std::string _base_topic_name = ""; - std::string _frame_id = ""; - }; - -} // 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..ef77af628b6 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/CarlaActorListPublisher.cpp @@ -0,0 +1,37 @@ +// 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 "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(); + topic_qos.keep_last(1); + topic_qos.force_synchronous_writer(); + 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..1309e70ee83 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/CarlaActorListPublisher.h @@ -0,0 +1,41 @@ +// 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/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 edb98ff4eae..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 d47d624dc1c..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 { - -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 = static_cast(static_cast(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 0242ac96d6c..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: - 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) * 3u + (event.pol ? 2u : 0u); - 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 d080de4f2e5..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 { - -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 e35d59cc550..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: - 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 7801657ea9c..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(static_cast(point_size)); - _impl->GetMessage()->row_step(static_cast(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 6148f727090..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 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 aceb1f6648a..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; -}; - -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 a7fe60511b1..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: - 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 8a87193d840..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 { - -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 a76e57c01fb..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: - 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..2d0902f6797 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/CarlaStatusPublisher.cpp @@ -0,0 +1,38 @@ +// 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 "CarlaStatusPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +CarlaStatusPublisher::CarlaStatusPublisher() + : PublisherBase(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(); + topic_qos.force_synchronous_writer(); + 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..260d5ee323d --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/CarlaStatusPublisher.h @@ -0,0 +1,40 @@ +// 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/PublisherBase.h" +#include "carla_msgs/msg/CarlaStatusPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using CarlaStatusPublisherImpl = DdsPublisherImpl; + +class CarlaStatusPublisher : public PublisherBase { +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 10e3c985d55..00000000000 --- a/LibCarla/source/carla/ros2/publishers/CarlaTransformPublisher.cpp +++ /dev/null @@ -1,89 +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 = it->second.first; - const auto& last_tf = it->second.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..32126763b0a --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ClockPublisher.cpp @@ -0,0 +1,33 @@ +// 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 "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().force_synchronous_writer()); +} + +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..f4bd80567eb --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ClockPublisher.h @@ -0,0 +1,44 @@ +// 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/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/ObjectPublisher.cpp b/LibCarla/source/carla/ros2/publishers/ObjectPublisher.cpp new file mode 100644 index 00000000000..9d16704902f --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectPublisher.cpp @@ -0,0 +1,39 @@ +// 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 "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_PUBLISHER_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..3341dcf3a67 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectPublisher.h @@ -0,0 +1,45 @@ +// 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/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..5f3727e96e7 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectWithCovariancePublisher.cpp @@ -0,0 +1,39 @@ +// 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 "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_PUBLISHER_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..45708937097 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectWithCovariancePublisher.h @@ -0,0 +1,45 @@ +// 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/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..41f514643a8 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectsPublisher.cpp @@ -0,0 +1,69 @@ +// 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 "ObjectsPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" +#include + +namespace carla { +namespace ros2 { + +ObjectsPublisher::ObjectsPublisher(ObjectsPublisher::ObjectMode const update_mode, std::string role_name) + : PublisherBase(carla::ros2::types::ActorNameDefinition::CreateFromRoleName(role_name)) + , _impl(std::make_shared()) + , _update_mode(update_mode) +{ + _impl->Message().header().frame_id("map"); +} + +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(); + if (_update_mode == ObjectsPublisher::ObjectMode::DYNAMIC_PUBLISH_ALWAYS) { + _impl->Message().objects().clear(); + } + return result; +} + +bool ObjectsPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void ObjectsPublisher::UpdateHeader(const builtin_interfaces::msg::Time &stamp) { + _impl->Message().header().stamp(stamp); + if ((_update_mode == ObjectsPublisher::ObjectMode::DYNAMIC_PUBLISH_ALWAYS) + || (_update_mode == ObjectsPublisher::ObjectMode::STATIC_PUBLISH_ONCE)) { + _impl->SetMessageUpdated(); + } +} + +void ObjectsPublisher::UpdateObject(std::shared_ptr &object) { + auto find_res = std::find_if(_impl->Message().objects().begin(), _impl->Message().objects().end(), + [object](derived_object_msgs::msg::Object &ros_object){ return ros_object.id()==object->actor_id(); }); + if (find_res != _impl->Message().objects().end()) { + if ( object->has_dynamic_data_changed(*find_res) ) + { + derived_object_msgs::msg::Object const ros_object = object->object(); + *find_res=ros_object; + _impl->SetMessageUpdated(); + } + } +} + +void ObjectsPublisher::AddObject(carla::ros2::types::Object const &object) { + derived_object_msgs::msg::Object ros_object = object.object(); + _impl->Message().objects().emplace_back(ros_object); +} + +void ObjectsPublisher::RemoveObject(uint64_t const object_id) { + std::remove_if(_impl->Message().objects().begin(), _impl->Message().objects().end(), + [object_id](derived_object_msgs::msg::Object &ros_object){ return ros_object.id()==object_id; }); +} + +} // 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..9f13846897e --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectsPublisher.h @@ -0,0 +1,60 @@ +// 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/PublisherBase.h" +#include "carla/ros2/types/Object.h" +#include "derived_object_msgs/msg/ObjectArrayPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using ObjectsPublisherImpl = + DdsPublisherImpl; + +class ObjectsPublisher : public PublisherBase { +public: + enum class ObjectMode { + DYNAMIC_PUBLISH_ALWAYS, + DYNAMIC_PUBLISH_ON_CHANGE, + STATIC_PUBLISH_ONCE + }; + + ObjectsPublisher(ObjectMode const update_mode, std::string role_name = "objects"); + 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 UpdateObject(std::shared_ptr &object); + + void AddObject(std::shared_ptr &object) + { + AddObject(*object); + } + + void AddObject(carla::ros2::types::Object const &object); + + void RemoveObject(uint64_t const object_id); + +private: + std::shared_ptr _impl; + ObjectMode const _update_mode; +}; +} // 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..364b458c9b6 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectsWithCovariancePublisher.cpp @@ -0,0 +1,41 @@ +// 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 "ObjectsWithCovariancePublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +ObjectsWithCovariancePublisher::ObjectsWithCovariancePublisher() + : PublisherBase(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(); + // after every frame clear the objects + _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..111cfdd8ad1 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/ObjectsWithCovariancePublisher.h @@ -0,0 +1,44 @@ +// 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/PublisherBase.h" +#include "carla/ros2/types/Object.h" +#include "derived_object_msgs/msg/ObjectWithCovarianceArrayPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using ObjectsWithCovariancePublisherImpl = + DdsPublisherImpl; + +class ObjectsWithCovariancePublisher : public PublisherBase { +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..e13de2bb456 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/PublisherBase.h @@ -0,0 +1,104 @@ +// 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/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) { + log_debug("PublisherBase created for topic ", actor_name_definition->ros_name); + } + virtual ~PublisherBase() { + log_debug("PublisherBase destroyed for topic ", _actor_name_definition->ros_name); + }; + + /** + * 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 + * + * see carla::ros2::DEFAULT_PUBLISHER_QOS + */ + 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; + } + + /* + * @brief is the publisher actually enabled for ROS tf publication + */ + virtual bool do_publish_tf(carla::streaming::detail::actor_id_type actor_id=0) const { + (void) actor_id; + return _actor_name_definition->publish_tf; + } + + + carla_msgs::msg::CarlaActorInfo carla_actor_info(std::shared_ptr name_registry = nullptr) const { + return _actor_name_definition->carla_actor_info(name_registry); + } + + /** + * Implement Message Processing in case the publisher has to do so. + */ + virtual void ProcessMessages() {}; + + /** + * Implement actions before sensor data updates + */ + virtual void UpdateSensorDataPreAction() {}; + + /** + * Implement actions after sensor data updates + */ + virtual void UpdateSensorDataPostAction() {} + +}; +} // 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..4ded84f6ad4 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/PublisherBaseTransform.h @@ -0,0 +1,82 @@ +// 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/PublisherBase.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 PublisherBase { +public: + using CoordinateSystemTransform = carla::ros2::types::CoordinateSystemTransform; + + PublisherBaseTransform(std::shared_ptr actor_name_definition, + std::shared_ptr transform_publisher, + TransformPublisher::TransformPublisherMode const mode) + : PublisherBase(actor_name_definition), _transform_publisher(transform_publisher), _mode(mode) {} + + virtual ~PublisherBaseTransform() { + // remove the transform from the TF tree when the publisher is destroyed + _transform_publisher->RemoveTransform(frame_id()); + } + + /** + * 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(), _mode); + } + + /** + * 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; + TransformPublisher::TransformPublisherMode _mode; +}; +} // 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 377058822fe..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 = static_cast(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..8a8440476b8 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/PublisherInterface.h @@ -0,0 +1,54 @@ +// 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 "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..ce0a1c88a44 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficLightPublisher.cpp @@ -0,0 +1,112 @@ +// 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 "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 traffic_lights_publisher) + : PublisherBase( + std::static_pointer_cast(traffic_light_actor_definition)) +#if PUBLISH_INDIVIDUAL_TRAFFIC_LIGHT_DATA + , _traffic_light_info_publisher(std::make_shared()) + , _traffic_light_status_publisher(std::make_shared()) + , _traffic_light_object_publisher(std::make_shared(*this, objects_publisher)) +#else + , _traffic_light_objects_publisher(objects_publisher) +#endif + , _traffic_lights_publisher(traffic_lights_publisher) { + _traffic_light_status.header().frame_id("map"); + _traffic_light_status.state(carla_msgs::msg::CarlaTrafficLightStatus_Constants::UNKNOWN); +} + +bool TrafficLightPublisher::Init(std::shared_ptr domain_participant) { + bool success = true; +#if PUBLISH_INDIVIDUAL_TRAFFIC_LIGHT_DATA + success &= _traffic_light_info_publisher->Init(domain_participant, get_topic_name("traffic_light_info"), + PublisherBase::get_topic_qos()); +success &= _traffic_light_status_publisher->Init(domain_participant, get_topic_name("traffic_light_status"), + PublisherBase::get_topic_qos()); +success &= _traffic_light_object_publisher->Init(domain_participant); +#endif + return success; +} + +bool TrafficLightPublisher::Publish() { + bool success = true; +#if PUBLISH_INDIVIDUAL_TRAFFIC_LIGHT_DATA + success &= _traffic_light_info_publisher->Publish(); + success &= _traffic_light_status_publisher->Publish(); + success &= _traffic_light_object_publisher->Publish(); +#endif + return success; +} + +bool TrafficLightPublisher::SubscribersConnected() const { + bool connected = false; +#if PUBLISH_INDIVIDUAL_TRAFFIC_LIGHT_DATA + connected |= _traffic_light_info_publisher->SubscribersConnected(); + connected |= _traffic_light_status_publisher->SubscribersConnected(); + connected |= _traffic_light_object_publisher->SubscribersConnected(); +#endif + return connected; +} + +void TrafficLightPublisher::UpdateTrafficLight(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &actor_dynamic_state) { + if ( (!_traffic_light_info_initialized) || (_traffic_light_info.transform() != object->Transform().pose())) { + _traffic_light_info_initialized = true; + _traffic_light_info.id(object->actor_id()); + _traffic_light_info.transform(object->Transform().pose()); + // trigger volume + auto traffic_light_actor_definition = std::dynamic_pointer_cast(_actor_name_definition); + if (traffic_light_actor_definition!=nullptr) + { + auto global_location = traffic_light_actor_definition->trigger_volume.location; + object->Transform().TransformPoint(global_location); + _traffic_light_info.trigger_volume().center().x(global_location.x); + _traffic_light_info.trigger_volume().center().y(global_location.y); + _traffic_light_info.trigger_volume().center().z(global_location.z); + auto const ros_extent = traffic_light_actor_definition->trigger_volume.extent * 2.; + _traffic_light_info.trigger_volume().size().x(ros_extent.x); + _traffic_light_info.trigger_volume().size().y(ros_extent.y); + _traffic_light_info.trigger_volume().size().z(ros_extent.z); + } + else + { + log_error("TrafficLightPublisher::UpdateTrafficLight(", std::to_string(*_actor_name_definition), + ") actor definition should be of type carla::ros2::types::TrafficLightActorDefinition"); + } +#if PUBLISH_INDIVIDUAL_TRAFFIC_LIGHT_DATA + _traffic_light_info_publisher->Message()=_traffic_light_info; + _traffic_light_info_publisher->SetMessageUpdated(); +#endif + _traffic_lights_publisher->UpdateTrafficLightInfo(_traffic_light_info); + } + + if (_traffic_light_status.state() != carla::ros2::types::GetTrafficLightState(actor_dynamic_state)) { + _traffic_light_status.id(_traffic_light_info.id()); + _traffic_light_status.state(carla::ros2::types::GetTrafficLightState(actor_dynamic_state)); + _traffic_light_status.header().stamp(object->Timestamp().time()); +#if PUBLISH_INDIVIDUAL_TRAFFIC_LIGHT_DATA + _traffic_light_status_publisher->Message()=_traffic_light_status; + _traffic_light_status_publisher->SetMessageUpdated(); +#endif + _traffic_lights_publisher->UpdateTrafficLightStatus(_traffic_light_status); + } +#if PUBLISH_INDIVIDUAL_TRAFFIC_LIGHT_DATA + _traffic_light_object_publisher->UpdateObject(object); +#else + _traffic_light_objects_publisher->UpdateObject(object); +#endif +} + +} // 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..783a7d6af14 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficLightPublisher.h @@ -0,0 +1,65 @@ +// 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/ObjectPublisher.h" +#include "carla/ros2/publishers/PublisherBase.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" + +#define PUBLISH_INDIVIDUAL_TRAFFIC_LIGHT_DATA 0 + +namespace carla { +namespace ros2 { + +using TrafficLightInfoPublisherImpl = + DdsPublisherImpl; +using TrafficLightStatusPublisherImpl = + DdsPublisherImpl; + +class TrafficLightPublisher : public PublisherBase { +public: + TrafficLightPublisher(std::shared_ptr traffic_light_actor_definition, + std::shared_ptr objects_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: + carla_msgs::msg::CarlaTrafficLightStatus _traffic_light_status; + carla_msgs::msg::CarlaTrafficLightInfo _traffic_light_info; + bool _traffic_light_info_initialized{false}; +#if PUBLISH_INDIVIDUAL_TRAFFIC_LIGHT_DATA + std::shared_ptr _traffic_light_info_publisher; + bool _traffic_light_info_published{false}; + std::shared_ptr _traffic_light_status_publisher; + std::shared_ptr _traffic_light_object_publisher; +#else + std::shared_ptr _traffic_light_objects_publisher; +#endif + 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..054ebc78869 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficLightsPublisher.cpp @@ -0,0 +1,73 @@ +// 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 "TrafficLightsPublisher.h" + +#include +#include "carla/ros2/impl/DdsPublisherImpl.h" + +namespace carla { +namespace ros2 { + +TrafficLightsPublisher::TrafficLightsPublisher() + : PublisherBase(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().keep_last(1)) && + _traffic_light_status->InitHistoryPreallocatedWithReallocMemoryMode( + domain_participant, get_topic_name("status"), PublisherBase::get_topic_qos().keep_last(1)); +} + +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..02e9560c382 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficLightsPublisher.h @@ -0,0 +1,48 @@ +// 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/PublisherBase.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 PublisherBase { +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..be9a8c51de3 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficSignPublisher.cpp @@ -0,0 +1,59 @@ +// 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 "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) + : PublisherBase( + std::static_pointer_cast(traffic_sign_actor_definition)) +#if PUBLISH_INDIVIDUAL_TRAFFIC_SIGN_DATA + , _traffic_sign_object_publisher(std::make_shared(*this, objects_publisher)) +#else + , _traffic_sign_objects_publisher(objects_publisher) +#endif + {} + +bool TrafficSignPublisher::Init(std::shared_ptr domain_participant) { + bool success = true; +#if PUBLISH_INDIVIDUAL_TRAFFIC_SIGN_DATA + success &= _traffic_sign_object_publisher->Init(domain_participant); +#endif + return success; +} + +bool TrafficSignPublisher::Publish() { + bool success = true; +#if PUBLISH_INDIVIDUAL_TRAFFIC_SIGN_DATA + success &= _traffic_sign_object_publisher->Publish(); +#endif + return success; +} + +bool TrafficSignPublisher::SubscribersConnected() const { + bool connected = false; +#if PUBLISH_INDIVIDUAL_TRAFFIC_SIGN_DATA + connected |= _traffic_sign_object_publisher->SubscribersConnected(); +#endif + return connected; +} + +void TrafficSignPublisher::UpdateTrafficSign(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &) { +#if PUBLISH_INDIVIDUAL_TRAFFIC_SIGN_DATA + _traffic_sign_object_publisher->UpdateObject(object); +#else + _traffic_sign_objects_publisher->UpdateObject(object); +#endif +} + +} // 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..d40cf2653ef --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TrafficSignPublisher.h @@ -0,0 +1,49 @@ +// 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/ObjectPublisher.h" +#include "carla/ros2/publishers/PublisherBase.h" +#include "carla/ros2/types/Object.h" +#include "carla/ros2/types/TrafficSignActorDefinition.h" +#include "carla/sensor/data/ActorDynamicState.h" + +#define PUBLISH_INDIVIDUAL_TRAFFIC_SIGN_DATA 0 + +namespace carla { +namespace ros2 { + +class TrafficSignPublisher : public PublisherBase { +public: + TrafficSignPublisher(std::shared_ptr traffic_sign_actor_definition, + std::shared_ptr objects_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: +#if PUBLISH_INDIVIDUAL_TRAFFIC_SIGN_DATA + std::shared_ptr _traffic_sign_object_publisher; +#else + std::shared_ptr _traffic_sign_objects_publisher; +#endif +}; +} // 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..e80aa7856a3 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TransformPublisher.cpp @@ -0,0 +1,91 @@ +// 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 . + +#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_tf(std::make_shared()), + _impl_tf_static(std::make_shared()) {} + +bool TransformPublisher::Init(std::shared_ptr domain_participant) { + auto topic_qos = get_topic_qos(); + topic_qos.force_synchronous_writer(); + return _impl_tf->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, "rt/tf", topic_qos) + && _impl_tf_static->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, "rt/tf_static", topic_qos); +} + +bool TransformPublisher::Publish() { + auto success = _impl_tf->Publish(); + success &= _impl_tf_static->Publish(); + // after every frame clear the dynamic tf tree + _impl_tf->Message().transforms().clear(); + return success; +} + +bool TransformPublisher::SubscribersConnected() const { + return _impl_tf->SubscribersConnected() || _impl_tf_static->SubscribersConnected(); +} + +void TransformPublisher::AddTransform(const builtin_interfaces::msg::Time &stamp, const std::string &name, const std::string &parent, + geometry_msgs::msg::Transform const &transform, TransformPublisher::TransformPublisherMode const mode) { + + geometry_msgs::msg::TransformStamped ts; + ts.header().frame_id(parent); + if ( name == parent ) { + // the child frame cannot be its own parent in ROS TF, so just ignore + return; + } + else { + ts.child_frame_id(name); + } + ts.header().stamp(stamp); + ts.transform(transform); + + if ( mode == TransformPublisherMode::MODE_STATIC ) { + bool found = false; + for (auto & t : _impl_tf_static->Message().transforms()) { + if (t.child_frame_id() == ts.child_frame_id()) { + // the child frame already exists in the static tf tree, so republish it only if necessary + // either the transform or the parent frame has changed + if (t.transform() != ts.transform() || t.header().frame_id() != ts.header().frame_id()) { + t = ts; + _impl_tf_static->SetMessageUpdated(); + } + found = true; + break; + } + } + if ( !found ) { + _impl_tf_static->Message().transforms().push_back(ts); + _impl_tf_static->SetMessageUpdated(); + } + } + else { + _impl_tf->Message().transforms().push_back(ts); + _impl_tf->SetMessageUpdated(); + } +} + +void TransformPublisher::RemoveTransform(const std::string &name) { + // remove the transform from the static tf tree if it exists there + for (auto it = _impl_tf_static->Message().transforms().begin(); it != _impl_tf_static->Message().transforms().end(); ++it) { + if (it->child_frame_id() == name) { + _impl_tf_static->Message().transforms().erase(it); + _impl_tf_static->SetMessageUpdated(); + return; + } + } +} + +} // 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..5fe0f0cb504 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/TransformPublisher.h @@ -0,0 +1,49 @@ +// 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/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; + + enum class TransformPublisherMode { + MODE_STATIC = 0, + MODE_DYNAMIC = 1 + }; + + void AddTransform(const builtin_interfaces::msg::Time &stamp, const std::string &name, const std::string &parent, + geometry_msgs::msg::Transform const &transform, TransformPublisherMode const mode); + void RemoveTransform(const std::string &name); + +private: + std::shared_ptr _impl_tf; + std::shared_ptr _impl_tf_static; +}; +} // 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..2e8039fda61 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeCollisionPublisher.cpp @@ -0,0 +1,42 @@ +// 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 "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) + : UePublisherBase(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..d793d16f531 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeCollisionPublisher.h @@ -0,0 +1,52 @@ +// 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/UePublisherBase.h" +#include "carla/sensor/s11n/CollisionEventSerializer.h" +#include "carla_msgs/msg/CarlaCollisionEventPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UeCollisionPublisherImpl = + DdsPublisherImpl; + +class UeCollisionPublisher : public UePublisherBase { +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 UePublisherBase::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..fd65a66815c --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeDVSCameraPublisher.cpp @@ -0,0 +1,123 @@ +// 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 "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); + + auto const camera_info = CreateCameraInfo(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_Constants::UINT16); + descriptor1.count(1); + sensor_msgs::msg::PointField descriptor2; + descriptor2.name("y"); + descriptor2.offset(offsetof(DVSEvent, y)); + descriptor2.datatype(sensor_msgs::msg::PointField_Constants::UINT16); + descriptor2.count(1); + sensor_msgs::msg::PointField descriptor3; + descriptor3.name("t"); + descriptor3.offset(offsetof(DVSEvent, t)); + descriptor3.datatype( + sensor_msgs::msg::PointField_Constants::FLOAT64); // PointField_Constants::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_Constants::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..a7c40e06243 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeDVSCameraPublisher.h @@ -0,0 +1,71 @@ +// 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/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 UePublisherBase::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..67e18f46e53 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeDepthCameraPublisher.cpp @@ -0,0 +1,17 @@ +// 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 "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..fcaf4b7886f --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeDepthCameraPublisher.h @@ -0,0 +1,21 @@ +// 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/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..d7f2e1290ed --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeGNSSPublisher.cpp @@ -0,0 +1,56 @@ +// 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 "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) + : UePublisherBase(sensor_actor_definition, transform_publisher), + _impl(std::make_shared()) + { + + if ( sensor_actor_definition->attributes.find("noise_lat_stddev") != sensor_actor_definition->attributes.end() ) { + _noise_lat_covar = std::stod(sensor_actor_definition->attributes["noise_lat_stddev"]); + _noise_lat_covar = _noise_lat_covar * _noise_lat_covar; // covariance = stddev^2 + } + if ( sensor_actor_definition->attributes.find("noise_lon_stddev") != sensor_actor_definition->attributes.end() ) { + _noise_lon_covar = std::stod(sensor_actor_definition->attributes["noise_lon_stddev"]); + _noise_lon_covar = _noise_lon_covar * _noise_lon_covar; // covariance = stddev^2 + } + if ( sensor_actor_definition->attributes.find("noise_alt_stddev") != sensor_actor_definition->attributes.end() ) { + _noise_alt_covar = std::stod(sensor_actor_definition->attributes["noise_alt_stddev"]); + _noise_alt_covar = _noise_alt_covar * _noise_alt_covar; // covariance = stddev^2 + } + } + +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); + _impl->Message().position_covariance_type(sensor_msgs::msg::NavSatFix_Constants::COVARIANCE_TYPE_DIAGONAL_KNOWN); + _impl->Message().position_covariance({ _noise_lat_covar, 0.0, 0.0, 0.0, _noise_lon_covar, 0.0, 0.0, 0.0, _noise_alt_covar }); +} +} // 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..fbca3491a6c --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeGNSSPublisher.h @@ -0,0 +1,57 @@ +// 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/UePublisherBase.h" +#include "carla/sensor/s11n/GnssSerializer.h" +#include "sensor_msgs/msg/NavSatFixPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UeGNSSPublisherImpl = DdsPublisherImpl; + +class UeGNSSPublisher : public UePublisherBase { +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 UePublisherBase::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; + + double _noise_lat_covar{0.}; + double _noise_lon_covar{0.}; + double _noise_alt_covar{0.}; +}; +} // 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..831fc333c9f --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeIMUPublisher.cpp @@ -0,0 +1,69 @@ +// 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 . + +#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) + : UePublisherBase(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()); + // the IMU message contains angular velocity in radians + _impl->Message().angular_velocity(carla::ros2::types::AngularVelocity(imu_data.gyroscope, + carla::ros2::types::AngularVelocity::AngularVelocityMode::RADIAN).angular_velocity()); + _impl->Message().linear_acceleration(carla::ros2::types::Acceleration(imu_data.accelerometer).linear_acceleration()); + + /* + 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..f7fc49d95c0 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeIMUPublisher.h @@ -0,0 +1,51 @@ +// 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/UePublisherBase.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 UePublisherBase { +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 UePublisherBase::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..0c131b76903 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeISCameraPublisher.cpp @@ -0,0 +1,17 @@ +// 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 "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..b4ba17f7509 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeISCameraPublisher.h @@ -0,0 +1,22 @@ +// 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/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..87750dac5f1 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeLidarPublisher.cpp @@ -0,0 +1,56 @@ +// 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 "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_Constants::FLOAT32); + descriptor1.count(1); + sensor_msgs::msg::PointField descriptor2; + descriptor2.name("y"); + descriptor2.offset(4); + descriptor2.datatype(sensor_msgs::msg::PointField_Constants::FLOAT32); + descriptor2.count(1); + sensor_msgs::msg::PointField descriptor3; + descriptor3.name("z"); + descriptor3.offset(8); + descriptor3.datatype(sensor_msgs::msg::PointField_Constants::FLOAT32); + descriptor3.count(1); + sensor_msgs::msg::PointField descriptor4; + descriptor4.name("intensity"); + descriptor4.offset(12); + descriptor4.datatype(sensor_msgs::msg::PointField_Constants::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..955470afdcf --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeLidarPublisher.h @@ -0,0 +1,29 @@ +// 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/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..2d991d0292c --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeNormalsCameraPublisher.cpp @@ -0,0 +1,17 @@ +// 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 "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..a3154f28c9c --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeNormalsCameraPublisher.h @@ -0,0 +1,24 @@ +// 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/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..00a54be2860 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeOpticalFlowCameraPublisher.cpp @@ -0,0 +1,110 @@ +// 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 "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..76a1dc25aad --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeOpticalFlowCameraPublisher.h @@ -0,0 +1,25 @@ +// 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/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/UePublisherBase.h b/LibCarla/source/carla/ros2/publishers/UePublisherBase.h new file mode 100644 index 00000000000..2130ac085f1 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UePublisherBase.h @@ -0,0 +1,89 @@ +// 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/PublisherBaseTransform.h" +#include "carla/ros2/types/SensorActorDefinition.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. + Usually sensors are not moving in respect to their parent in the TF tree, so the transform is published as static and only updated if the sensor's position relatively to the parent changes. + */ +class UePublisherBase : public PublisherBaseTransform { +public: + UePublisherBase(std::shared_ptr sensor_actor_definition, + std::shared_ptr transform_publisher) + : PublisherBaseTransform(sensor_actor_definition, transform_publisher, + TransformPublisher::TransformPublisherMode::MODE_STATIC) {} + + virtual ~UePublisherBase() = default; + + /** + * Function to update the data for this sensor + */ + virtual void UpdateSensorData( + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) = 0; + + void UpdateSensorDataAndCheckPublish(uint64_t frame_id, + std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) { + + UpdateSensorData(sensor_header, buffer_view); + sensor_data_update_frame_id.store(frame_id); + if ( sensor_data_post_action_frame_id.load() >= frame_id ) { + // camera sensors trigger their data streams from the rendering thread + // therefore, the UpdateSensorDataPostAction() of the world publisher (running in the game thread) + // might have already been called for the current frame, which usually triggers the publishing of the sensor data. + // In this case, we need to force a publish here to make sure the data gets published in a timely manner. + log_verbose("Sensor Data to ROS data: frame.(", frame_id, ") stream.", + std::to_string(*std::static_pointer_cast(_actor_name_definition)), + " Late publishing in CheckPublishAfterDataUpdate()."); + Publish(); + } + } + + /** + * calling UpdateSensorDataPostAction but store frame_id for later use + */ + void UpdateSensorDataPostActionAndCheckPublish(uint64_t frame_id) { + sensor_data_post_action_frame_id.store(frame_id); + UpdateSensorDataPostAction(); + if (sensor_data_update_frame_id.load() >= frame_id) { + // If the sensor data stream already updated the data for this frame, we publish in here + // which is the standard for all UePublisher + // If not, then either that UePublisher has nothing to publish this frame, or its stream + // didn't yet update it's data. In both cases we don't need to publish now. + // In the later case publishing will be triggered in UpdateSensorDataAndCheckPublish() at a later point in time. + log_verbose("Sensor Data to ROS data: frame.(", frame_id, ") stream.", + std::to_string(*std::static_pointer_cast(_actor_name_definition)), + " Standard publishing in UpdateSensorDataPostActionAndCheckPublish()."); + Publish(); + } + } + + 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); + } + +private: + std::atomic sensor_data_post_action_frame_id{0u}; + std::atomic sensor_data_update_frame_id{0u}; +}; +} // 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..76e4f528bc0 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UePublisherBaseCamera.cc @@ -0,0 +1,121 @@ +// 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 "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) + : UePublisherBase(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 +sensor_msgs::msg::CameraInfo UePublisherBaseCamera::CreateCameraInfo(uint32_t height, uint32_t width, double fov) +{ + sensor_msgs::msg::CameraInfo camera_info; + camera_info.height(height); + camera_info.width(width); + camera_info.distortion_model("plumb_bob"); + + 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; + + camera_info.d({ 0.0, 0.0, 0.0, 0.0, 0.0 }); + camera_info.k({fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0}); + camera_info.r({ 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0 }); + camera_info.p({fx, 0.0, cx, 0.0, 0.0, fy, cy, 0.0, 0.0, 0.0, 1.0, 0.0}); + + camera_info.binning_x(0); + camera_info.binning_y(0); + + camera_info.roi().x_offset(0); // up-to-data: constantly 0 + camera_info.roi().y_offset(0); // up-to-data: constantly 0 + camera_info.roi().height(camera_info.height()); + camera_info.roi().width(camera_info.width()); + camera_info.roi().do_rectify(true); // up-to-data: constantly true + + return camera_info; +} + +template +void UePublisherBaseCamera::UpdateCameraInfo(const builtin_interfaces::msg::Time &stamp, + sensor_msgs::msg::CameraInfo const &camera_info) { + _camera_info->Message() = camera_info; + _camera_info->SetMessageHeader(stamp, frame_id()); + _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 auto camera_info = CreateCameraInfo(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..d268a382f96 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UePublisherBaseCamera.h @@ -0,0 +1,212 @@ +// 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/Exception.h" +#include "carla/ros2/publishers/UePublisherBase.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 UePublisherBase 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 UePublisherBase { +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 UePublisherBase::UpdateSensorData() interface + */ + void UpdateSensorData(std::shared_ptr sensor_header, + const carla::SharedBufferView buffer_view) override; + +protected: + sensor_msgs::msg::CameraInfo CreateCameraInfo(uint32_t height, uint32_t width, double fov); + + 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..87dab48d9c6 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UePublisherBasePointCloud.cc @@ -0,0 +1,55 @@ +// 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 "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) + : UePublisherBase(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 uint32_t point_size = static_cast(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..a4252766207 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UePublisherBasePointCloud.h @@ -0,0 +1,74 @@ +// 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/UePublisherBase.h" +#include "sensor_msgs/msg/PointCloud2PubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UePublisherPointCloudImpl = + DdsPublisherImpl; + +/** + A Publisher base class for point cloud publisher sensors. + Extends UePublisherBase by an point cloud publisher. +*/ +template +class UePublisherBasePointCloud : public UePublisherBase { +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 UePublisherBase::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/UeRGBCameraPublisher.cpp b/LibCarla/source/carla/ros2/publishers/UeRGBCameraPublisher.cpp new file mode 100644 index 00000000000..18f771a0af3 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeRGBCameraPublisher.cpp @@ -0,0 +1,39 @@ +// 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 "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, + carla::ros2::types::ActorSetTransformCallback actor_set_transform_callback) + : UePublisherBaseCamera(sensor_actor_definition, transform_publisher) + , actor_set_transform_subscriber(std::make_shared( + *this, actor_set_transform_callback)) + {} + +bool UeRGBCameraPublisher::Init(std::shared_ptr domain_participant) { + _initialized = UePublisherBaseCamera::Init(domain_participant); + _initialized &= actor_set_transform_subscriber->Init(domain_participant); + return _initialized; +} + +void UeRGBCameraPublisher::ProcessMessages() { + if (!_initialized) { + return; + } + actor_set_transform_subscriber->ProcessMessages(); +} + + + + + +} // 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..7e6a4f8471c --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeRGBCameraPublisher.h @@ -0,0 +1,38 @@ +// 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/UePublisherBaseCamera.h" +#include "carla/ros2/subscribers/ActorSetTransformSubscriber.h" +#include "carla/ros2/types/SensorActorDefinition.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, + carla::ros2::types::ActorSetTransformCallback actor_set_transform_callback); + virtual ~UeRGBCameraPublisher() = default; + + /** + * Implements ROS2NameRecord::Init() interface + */ + bool Init(std::shared_ptr domain_participant) override; + + /** + * Process incoming messages. + */ + void ProcessMessages() override; + +private: + std::shared_ptr actor_set_transform_subscriber; + bool _initialized{false}; +}; +} // 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..076a8dbda45 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeRadarPublisher.cpp @@ -0,0 +1,84 @@ +// 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 "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_Constants::FLOAT32); + descriptor1.count(1); + sensor_msgs::msg::PointField descriptor2; + descriptor2.name("y"); + descriptor2.offset(4); + descriptor2.datatype(sensor_msgs::msg::PointField_Constants::FLOAT32); + descriptor2.count(1); + sensor_msgs::msg::PointField descriptor3; + descriptor3.name("z"); + descriptor3.offset(8); + descriptor3.datatype(sensor_msgs::msg::PointField_Constants::FLOAT32); + descriptor3.count(1); + sensor_msgs::msg::PointField descriptor4; + descriptor4.name("velocity"); + descriptor4.offset(12); + descriptor4.datatype(sensor_msgs::msg::PointField_Constants::FLOAT32); + descriptor4.count(1); + sensor_msgs::msg::PointField descriptor5; + descriptor5.name("azimuth"); + descriptor5.offset(16); + descriptor5.datatype(sensor_msgs::msg::PointField_Constants::FLOAT32); + descriptor5.count(1); + sensor_msgs::msg::PointField descriptor6; + descriptor6.name("altitude"); + descriptor6.offset(20); + descriptor6.datatype(sensor_msgs::msg::PointField_Constants::FLOAT32); + descriptor6.count(1); + sensor_msgs::msg::PointField descriptor7; + descriptor7.name("depth"); + descriptor7.offset(24); + descriptor7.datatype(sensor_msgs::msg::PointField_Constants::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..2248e3a2559 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeRadarPublisher.h @@ -0,0 +1,51 @@ +// 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/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..98590d33682 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeSSCameraPublisher.cpp @@ -0,0 +1,17 @@ +// 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 "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..b7d76c5505a --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeSSCameraPublisher.h @@ -0,0 +1,21 @@ +// 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/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..982ab48d0aa --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeSemanticLidarPublisher.cpp @@ -0,0 +1,68 @@ +// 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 "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_Constants::FLOAT32); + descriptor1.count(1); + sensor_msgs::msg::PointField descriptor2; + descriptor2.name("y"); + descriptor2.offset(4); + descriptor2.datatype(sensor_msgs::msg::PointField_Constants::FLOAT32); + descriptor2.count(1); + sensor_msgs::msg::PointField descriptor3; + descriptor3.name("z"); + descriptor3.offset(8); + descriptor3.datatype(sensor_msgs::msg::PointField_Constants::FLOAT32); + descriptor3.count(1); + sensor_msgs::msg::PointField descriptor4; + descriptor4.name("cos_inc_angle"); + descriptor4.offset(12); + descriptor4.datatype(sensor_msgs::msg::PointField_Constants::FLOAT32); + descriptor4.count(1); + sensor_msgs::msg::PointField descriptor5; + descriptor5.name("object_idx"); + descriptor5.offset(16); + descriptor5.datatype(sensor_msgs::msg::PointField_Constants::UINT32); + descriptor5.count(1); + sensor_msgs::msg::PointField descriptor6; + descriptor6.name("object_tag"); + descriptor6.offset(20); + descriptor6.datatype(sensor_msgs::msg::PointField_Constants::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..b8ac5c465dd --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeSemanticLidarPublisher.h @@ -0,0 +1,28 @@ +// 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/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..b8bd3a85946 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeV2XCustomPublisher.cpp @@ -0,0 +1,64 @@ +// 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 "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) + : UePublisherBase(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() { + auto const success = _impl->Publish(); + // clear old data after publishing + _impl->Message().data().clear(); + return success; +} +bool UeV2XCustomPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void UeV2XCustomPublisher::ProcessMessages() +{ + 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); + + 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..0a392629888 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeV2XCustomPublisher.h @@ -0,0 +1,65 @@ +// 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/UePublisherBase.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 UePublisherBase { +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 PublisherBase::ProcessMessages() + */ + void ProcessMessages() override; + /** + * Implements UePublisherBase::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..cd1dbab79fd --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeV2XPublisher.cpp @@ -0,0 +1,158 @@ +// 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 "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) + : UePublisherBase(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() { + auto const success = _impl->Publish(); + // clear old data after publishing + _impl->Message().data().clear(); + return success; +} +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); + + 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..3efc3b3e56d --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeV2XPublisher.h @@ -0,0 +1,58 @@ +// 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/UePublisherBase.h" +#include "carla/sensor/data/V2XEvent.h" +#include "carla_msgs/msg/CarlaV2XDataListPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using UeV2XPublisherImpl = DdsPublisherImpl; + +class UeV2XPublisher : public UePublisherBase { +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 UePublisherBase::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..1bb9bacd9a9 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeWorldPublisher.cpp @@ -0,0 +1,981 @@ +// 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 "UeWorldPublisher.h" + +#include "carla/sensor/data/RawEpisodeState.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/UeV2XPublisher.h" +#include "carla/ros2/publishers/UeV2XCustomPublisher.h" +#include "carla/ros2/publishers/VehiclePublisher.h" +#include "carla/ros2/subscribers/AckermannControlSubscriber.h" +#include "carla/ros2/subscribers/VehicleControlSubscriber.h" +#include "carla/ros2/types/EpisodeSettings.h" + + +#include "carla/ros2/types/Acceleration.h" +#include "carla/ros2/types/AngularVelocity.h" +#include "carla/ros2/types/Quaternion.h" +#include "carla/ros2/types/VehicleAckermannControl.h" +#include "carla/ros2/types/VehicleControl.h" + +namespace carla { +namespace ros2 { + + +UeWorldPublisher::UeWorldPublisher(carla::rpc::RpcServerInterface& carla_server, + std::shared_ptr name_registry, + std::shared_ptr sensor_actor_definition) + : UePublisherBase(sensor_actor_definition, std::make_shared()), + _carla_server(carla_server), + _name_registry(name_registry), + _clock_publisher(std::make_shared()), + _world_info_publisher(std::make_shared(_carla_server)), + _status_publisher(std::make_shared()), + _weather_publisher(std::make_shared(_carla_server)), + _sensor_actor_list_publisher(std::make_shared("sensor_list")), + _actor_list_publisher(std::make_shared("actor_list")), + _objects_publisher(std::make_shared(ObjectsPublisher::ObjectMode::DYNAMIC_PUBLISH_ALWAYS, "objects")), + _objects_with_covariance_publisher(std::make_shared()), + _traffic_lights_publisher(std::make_shared()), + _traffic_light_actor_list_publisher(std::make_shared("traffic_lights/actor_list")), + _traffic_light_objects_publisher(std::make_shared(ObjectsPublisher::ObjectMode::DYNAMIC_PUBLISH_ON_CHANGE, "traffic_lights/objects")), + _traffic_sign_actor_list_publisher(std::make_shared("traffic_signs/actor_list")), + _traffic_sign_objects_publisher(std::make_shared(ObjectsPublisher::ObjectMode::DYNAMIC_PUBLISH_ON_CHANGE, "traffic_signs/objects")), + _environment_actor_list_publisher(std::make_shared("environment/actor_list")), + _environment_objects_publisher(std::make_shared(ObjectsPublisher::ObjectMode::STATIC_PUBLISH_ONCE, "environment/objects")), + _carla_control_subscriber(std::make_shared(*this, _carla_server)), + _sync_subscriber(std::make_shared(*this, _carla_server)), + _weather_control_subscriber(std::make_shared(*this, _carla_server)) { + + _dispatcher = _carla_server.GetDispatcher(); +} + +bool UeWorldPublisher::Init(std::shared_ptr domain_participant) { + // add this to the list of sensors first + auto sensor_ue = AddSensorUeInternal(GetSensorActorDefinition()); + sensor_ue->publisher=std::static_pointer_cast(shared_from_this()); + + _domain_participant_impl = domain_participant; + _initialized = + _transform_publisher->Init(domain_participant) && + _clock_publisher->Init(domain_participant) && + _world_info_publisher->Init(domain_participant) && + _status_publisher->Init(domain_participant) && + _weather_publisher->Init(domain_participant) && + _sensor_actor_list_publisher->Init(_domain_participant_impl) && + _actor_list_publisher->Init(domain_participant) && + _objects_publisher->Init(domain_participant) && + _objects_with_covariance_publisher->Init(domain_participant) && + _traffic_lights_publisher->Init(domain_participant) && + _traffic_light_actor_list_publisher->Init(_domain_participant_impl) && + _traffic_light_objects_publisher->Init(domain_participant) && + _traffic_sign_actor_list_publisher->Init(_domain_participant_impl) && + _traffic_sign_objects_publisher->Init(domain_participant) && + _environment_actor_list_publisher->Init(domain_participant) && + _environment_objects_publisher->Init(domain_participant) && + _carla_control_subscriber->Init(domain_participant) && + _weather_control_subscriber->Init(domain_participant) && + _sync_subscriber->Init(domain_participant); + return _initialized; +} + +void UeWorldPublisher::Cleanup() { + _objects.clear(); + _vehicles.clear(); + _walkers.clear(); + _traffic_lights.clear(); + _traffic_signs.clear(); + _ue_sensors.clear(); +} + +bool UeWorldPublisher::Publish() { + // publishing is performed in an ordered manner in the UpdateSensorDataPostAction() + // this is to ensure that the clock and TF messages are published before the other messages, which might depend on them. + return true; +} + +void UeWorldPublisher::ProcessMessages() { + if (!_initialized) { + return; + } + + _carla_control_subscriber->ProcessMessages(); + _sync_subscriber->ProcessMessages(); + _weather_control_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(); + } + for (auto &ue_sensor : _ue_sensors) { + if ( (ue_sensor.second.publisher != nullptr) && (ue_sensor.first != GetSensorActorDefinition()->stream_id) ) { + ue_sensor.second.publisher->ProcessMessages(); + } + } + + UpdateAndPublishEnvironmentObjects(); + UpdateAndPublishStatus(); +} + +void UeWorldPublisher::UpdateSensorDataPreAction() { + 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_debug("UeWorldPublisher::UpdateSensorDataPreAction[", 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_debug("UeWorldPublisher::UpdateSensorDataPreAction[", std::to_string(*ue_sensor.second.sensor_actor_definition()), + "]: Deregistering session"); + _dispatcher->DeregisterSession(ue_sensor.second.session); + ue_sensor.second.session.reset(); + } + } + } + + _world_info_publisher->UpdateSensorDataPreAction(); + _weather_publisher->UpdateSensorDataPreAction(); + + for (auto &ue_sensor : _ue_sensors) { + if ( (ue_sensor.second.publisher != nullptr) && (ue_sensor.first != GetSensorActorDefinition()->stream_id) ) { + ue_sensor.second.publisher->UpdateSensorDataPreAction(); + } + } + for (auto& vehicle : _vehicles) { + auto publisher = vehicle.second._vehicle_publisher; + if (publisher != nullptr) { + publisher->UpdateSensorDataPreAction(); + } + } + for (auto& walker : _walkers) { + auto publisher = walker.second._walker_publisher; + if (publisher != nullptr) { + publisher->UpdateSensorDataPreAction(); + } + } + for (auto& traffic_light : _traffic_lights) { + auto publisher = traffic_light.second._traffic_light_publisher; + if (publisher != nullptr) { + publisher->UpdateSensorDataPreAction(); + } + } + + + if (_sensors_changed) { + _sensors_changed = false; + carla_msgs::msg::CarlaActorList actor_list; + for (auto &ue_sensor : _ue_sensors) { + if (ue_sensor.second.sensor_actor_definition()->id != 0) { + actor_list.actors().push_back(ue_sensor.second.sensor_actor_definition()->carla_actor_info(_name_registry)); + } + } + _sensor_actor_list_publisher->UpdateCarlaActorList(actor_list); + } +} + +void UeWorldPublisher::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()) { + if (ue_sensor->second.publisher->do_publish_tf() ) { + ue_sensor->second.publisher->UpdateTransform(sensor_header); + } + ue_sensor->second.publisher->UpdateSensorDataAndCheckPublish(CurrentFrame(), sensor_header, *data_view_iter); + } + log_verbose("Sensor Data to ROS data: frame.(", CurrentFrame(), ") stream.", + std::to_string(*sensor_actor_definition), " Processed."); + + } else { + log_verbose("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."); + } + + } else { + log_error("Sensor Data to ROS data: frame.(", CurrentFrame(), ") stream.", std::to_string(stream_id), + " not registered. Dropping data."); + } +} + +void UeWorldPublisher::UpdateSensorDataPostAction() { + if (!_initialized) { + return; + } + + // the actual publishing of data is triggered here for most of the data + // first the data is collected by the sensor updates and then published here in an ordered manner. + // This is to ensure that the clock and TF messages are published before the other messages, which might depend on them. + // Most of the ROS2 applications might not have an issue with slightly later published clock and TF messages, + // but some applications (e.g. rviz) might require the clock and TF messages to be published before the other messages. + + _transform_publisher->Publish(); + _clock_publisher->Publish(); + UpdateAndPublishStatus(); + _world_info_publisher->Publish(); + _weather_publisher->Publish(); + _actor_list_publisher->Publish(); + _sensor_actor_list_publisher->Publish(); + _objects_publisher->Publish(); + _objects_with_covariance_publisher->Publish(); + _traffic_lights_publisher->Publish(); + _traffic_light_actor_list_publisher->Publish(); + _traffic_light_objects_publisher->Publish(); + _traffic_sign_actor_list_publisher->Publish(); + _traffic_sign_objects_publisher->Publish(); + + for (auto& vehicle : _vehicles) { + auto publisher = vehicle.second._vehicle_publisher; + if (publisher != nullptr) { + publisher->UpdateSensorDataPostAction(); + publisher->Publish(); + } + } + for (auto& walker : _walkers) { + auto publisher = walker.second._walker_publisher; + if (publisher != nullptr) { + publisher->UpdateSensorDataPostAction(); + publisher->Publish(); + } + } + for (auto& traffic_light : _traffic_lights) { + auto publisher = traffic_light.second._traffic_light_publisher; + if (publisher != nullptr) { + publisher->UpdateSensorDataPostAction(); + publisher->Publish(); + } + } + for (auto& traffic_sign : _traffic_signs) { + auto publisher = traffic_sign.second._traffic_sign_publisher; + if (publisher != nullptr) { + publisher->Publish(); + } + } + + for (auto &ue_sensor : _ue_sensors) { + if ( (ue_sensor.second.publisher != nullptr) && (ue_sensor.first != GetSensorActorDefinition()->stream_id) ) { + ue_sensor.second.publisher->UpdateSensorDataPostActionAndCheckPublish(CurrentFrame()); + } + } + +} + +void UeWorldPublisher::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: + case types::PublisherSensorType::HSSLidar: + { + 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, sensor.actor_set_transform_callback)); + } 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::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::WorldObserver: + 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("UeWorldPublisher::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("UeWorldPublisher::CreateSensorUePublisher[", std::to_string(*sensor.sensor_actor_definition()), + "]: Failed to init publisher"); + } else { + log_debug("UeWorldPublisher::CreateSensorUePublisher[", std::to_string(*sensor.sensor_actor_definition()), + "]: Publisher initialized"); + } + } +} + +UeWorldPublisher::UeSensor* UeWorldPublisher::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("UeWorldPublisher::AddSensorUe(", std::to_string(*sensor_actor_definition), + "): Sensor already_registered. Ignoring"); + return nullptr; + } + _sensors_changed = true; + return &insert_result.first->second; +} + +void UeWorldPublisher::AddSensorUe(std::shared_ptr sensor_actor_definition, + carla::ros2::types::ActorSetTransformCallback actor_set_transform_callback) { + auto ue_sensor = AddSensorUeInternal(sensor_actor_definition); + if ( ue_sensor != nullptr ) { + ue_sensor->actor_set_transform_callback = actor_set_transform_callback; + } +} + +void UeWorldPublisher::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; + } +} + +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, _carla_server); + 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; + } + _traffic_light_objects_publisher->AddObject(*object); + _traffic_lights_changed = true; + + auto traffic_light_publisher = std::make_shared(traffic_light_actor_definition, + _traffic_light_objects_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; + } + _traffic_sign_objects_publisher->AddObject(*object); + _traffic_signs_changed = true; + + auto traffic_sign_publisher = + std::make_shared(traffic_sign_actor_definition, _traffic_sign_objects_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); + auto vehicle_iter = _vehicles.find(actor); + if ( vehicle_iter != _vehicles.end() ) { + log_debug("ROS2::RemoveVehicleUe(", std::to_string( + *std::static_pointer_cast(vehicle_iter->second._vehicle_publisher->_actor_name_definition)), ")"); + _vehicles.erase(vehicle_iter); + _objects_changed = true; + } + auto walker_iter = _walkers.find(actor); + if ( walker_iter != _walkers.end() ) { + log_debug("ROS2::RemoveWalkerUe(", std::to_string( + *std::static_pointer_cast(walker_iter->second._walker_publisher->_actor_name_definition)), ")"); + _walkers.erase(walker_iter); + _objects_changed = true; + } + auto traffic_light_iter = _traffic_lights.find(actor); + if ( traffic_light_iter != _traffic_lights.end() ) { + log_debug("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_changed = true; + } + _traffic_lights_publisher->RemoveTrafficLight(actor); + _traffic_light_objects_publisher->RemoveObject(actor); + + auto traffic_sign_iter = _traffic_signs.find(actor); + if ( traffic_sign_iter != _traffic_signs.end() ) { + log_debug("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); + _traffic_signs_changed = true; + } + _traffic_sign_objects_publisher->RemoveObject(actor); + + auto sensor_iter = find_ue_sensor(actor); + if (sensor_iter!=_ue_sensors.end()) { + log_debug("ROS2::RemoveSensorUe(", std::to_string(*sensor_iter->second.sensor_actor_definition()), ")"); + _ue_sensors.erase(sensor_iter); + _sensors_changed = true; + } +} + +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()); + _status_publisher->UpdateCarlaStatus(status); + _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) { + _world_info_publisher->SetMapUpdated(); + } + + for (auto const& actor_dynamic_state : buffer_data_2_vector(buffer_view)) { + bool actor_processed = false; + carla::ros2::types::Transform transform(actor_dynamic_state.transform, actor_dynamic_state.quaternion); + + auto object_it = _objects.find(actor_dynamic_state.id); + if (object_it != _objects.end()) { + object_it->second->UpdateObject(_timestamp, actor_dynamic_state); + + std::shared_ptr object = object_it->second; + + auto vehicle_it = _vehicles.find(actor_dynamic_state.id); + if (vehicle_it != _vehicles.end()) { + actor_processed=true; + UeVehicle& ue_vehicle = vehicle_it->second; + auto publisher = ue_vehicle._vehicle_publisher; + if ( publisher->is_enabled_for_ros() ) { + if ( publisher->do_publish_tf() ) { + publisher->UpdateTransform(_timestamp, transform); + } + publisher->UpdateVehicle(object, actor_dynamic_state); + } + } + + if ( !actor_processed ) { + auto walker_it = _walkers.find(actor_dynamic_state.id); + if (walker_it != _walkers.end()) { + actor_processed=true; + UeWalker& ue_walker = walker_it->second; + auto publisher = ue_walker._walker_publisher; + if ( publisher->is_enabled_for_ros() ) { + if ( publisher->do_publish_tf() ) { + publisher->UpdateTransform(_timestamp, transform); + } + publisher->UpdateWalker(object, actor_dynamic_state); + } + } + } + + if ( !actor_processed ) { + auto traffic_sign_it = _traffic_signs.find(actor_dynamic_state.id); + if (traffic_sign_it != _traffic_signs.end()) { + actor_processed=true; + UeTrafficSign& ue_traffic_sign = traffic_sign_it->second; + auto publisher = ue_traffic_sign._traffic_sign_publisher; + if ( publisher->is_enabled_for_ros() ) { + publisher->UpdateTrafficSign(object, actor_dynamic_state); + } + } + } + + if ( !actor_processed ) { + auto traffic_light_it = _traffic_lights.find(actor_dynamic_state.id); + if (traffic_light_it != _traffic_lights.end()) { + actor_processed=true; + UeTrafficLight& ue_traffic_light = traffic_light_it->second; + auto publisher = ue_traffic_light._traffic_light_publisher; + if ( publisher->is_enabled_for_ros() ) { + publisher->UpdateTrafficLight(object, actor_dynamic_state); + } + } + } + } + + if ( !actor_processed ) { + auto sensor_it = find_ue_sensor(actor_dynamic_state.id); + if ( sensor_it != _ue_sensors.end() ) { + actor_processed=true; + // store the transform to be able to calculate relative transform in case of nested sensors + sensor_it->second.transform = transform; + } + } + } + + for (auto &ue_sensor : _ue_sensors) { + if ( (ue_sensor.second.publisher != nullptr) && + (ue_sensor.first != GetSensorActorDefinition()->stream_id) && + (ue_sensor.second.publisher->is_enabled_for_ros()) && + (ue_sensor.second.publisher->do_publish_tf())) { + // update sensor transform of sensors: + // - have to cover not subscribed sensors, as their data stream is not deployed + // - have to cover PixelCamera sensors, as they are publishing their data stream within the rendering thread + // and therefore might update their Transform possibly after the UpdateSensorDataPostAction() of the world publisher is called. + // In this case, we need to make sure the transform is updated before the data gets published. + // Since the UE sensor transform is published as static tf, calling the UpdateTransform() twice doesn't duplicate the TF messages. + auto const parent_actor_id = ue_sensor.second.publisher->get_parent_actor_id(); + auto const parent_transform = get_transform(parent_actor_id); + auto const relative_transform = ue_sensor.second.transform.GetRelativeTransform(parent_transform); + ue_sensor.second.publisher->UpdateTransform(_timestamp, relative_transform); + } + } + + if (_objects_changed) { + _objects_changed = false; + carla_msgs::msg::CarlaActorList actor_list; + for (auto const& vehicle : _vehicles) { + actor_list.actors().push_back(vehicle.second._vehicle_publisher->carla_actor_info(_name_registry)); + } + for (auto const& walker : _walkers) { + actor_list.actors().push_back(walker.second._walker_publisher->carla_actor_info(_name_registry)); + } + _actor_list_publisher->UpdateCarlaActorList(actor_list); + } + if (_traffic_lights_changed) { + _traffic_lights_changed = false; + carla_msgs::msg::CarlaActorList actor_list; + for (auto const& traffic_light : _traffic_lights) { + actor_list.actors().push_back(traffic_light.second._traffic_light_publisher->carla_actor_info(_name_registry)); + } + _traffic_light_actor_list_publisher->UpdateCarlaActorList(actor_list); + } + _traffic_light_objects_publisher->UpdateHeader(_timestamp.time()); + + if (_traffic_signs_changed) { + _traffic_signs_changed = false; + carla_msgs::msg::CarlaActorList actor_list; + for (auto const& traffic_sign : _traffic_signs) { + actor_list.actors().push_back(traffic_sign.second._traffic_sign_publisher->carla_actor_info(_name_registry)); + } + _traffic_sign_actor_list_publisher->UpdateCarlaActorList(actor_list); + } + _traffic_sign_objects_publisher->UpdateHeader(_timestamp.time()); +} + +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(); + } + auto sensor_it = find_ue_sensor(actor_id); + if (sensor_it != _ue_sensors.end()) { + if ( !sensor_it->second.publisher->is_enabled_for_ros() ) { + log_debug("Enable Sensor for ROS: ", + std::to_string(*sensor_it->second.publisher->_actor_name_definition)); + sensor_it->second.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(); + } + auto sensor_it = find_ue_sensor(actor_id); + if (sensor_it != _ue_sensors.end()) { + if ( sensor_it->second.publisher->is_enabled_for_ros() ) { + log_debug("Disable Sensor for ROS: ", + std::to_string(*sensor_it->second.publisher->_actor_name_definition)); + sensor_it->second.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(); + } + auto sensor_it = find_ue_sensor(actor_id); + if (sensor_it != _ue_sensors.end()) { + return sensor_it->second.publisher->is_enabled_for_ros(); + } + return false; +} + +void UeWorldPublisher::UpdateAndPublishEnvironmentObjects() +{ + if (!_initialized) + { + return; + } + + // The world observer enabled_for_ros flag is matching the ROS2TopicVisibility configuration value which is used to decide + // on the publication of the environment objects at this point + // Otherwhise one might have to define some enable_for_ros() calls for e.g. different carla::rpc::CityObjectLabel parameters + // if a fine granular selection will be required. + bool const ros2_topic_visibility = PublisherBase::is_enabled_for_ros(0); + if ( !ros2_topic_visibility) + { + return; + } + + if ( !_environment_objects_initialized ) + { + carla_msgs::msg::CarlaActorList actor_list; + for (auto label: {carla::rpc::CityObjectLabel::Any}) + { + auto response = _carla_server.call_get_environment_objects(static_cast(label)); + if ( !response.HasError() ) + { + auto const &environment_objects = response.Get(); + for (auto const& env_object : environment_objects) + { + auto const object = carla::ros2::types::Object(env_object, ros2_topic_visibility); + _environment_objects_publisher->AddObject(object); + actor_list.actors().push_back(object.carla_actor_info()); + } + } + } + if (!actor_list.actors().empty()) { + _environment_actor_list_publisher->UpdateCarlaActorList(actor_list); + _environment_objects_publisher->UpdateHeader(_timestamp.time()); + + _environment_objects_initialized = _environment_actor_list_publisher->Publish(); + _environment_objects_initialized &= _environment_objects_publisher->Publish(); + + log_debug("ROS2::UpdateAndPublishEnvironmentObjects() = ", actor_list.actors().size(), _environment_objects_initialized); + } + } +} + +void UeWorldPublisher::AttachActors(ActorId const child, ActorId const parent) { + log_debug("UeWorldPublisher::AttachActors[", child, "]: parent=", parent); + _name_registry->AttachActors(child, parent); + auto find_result = find_ue_sensor(child); + if ( find_result != _ue_sensors.end()) { + UeSensor &sensor = find_result->second; + if (sensor.publisher) { + log_error("UeWorldPublisher::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(); + } + _sensors_changed = true; + } +} + +std::unordered_map::iterator +UeWorldPublisher::find_ue_sensor(ActorId actor_id) +{ + auto find_result = std::find_if(_ue_sensors.begin(), _ue_sensors.end(), + [actor_id](std::pair element) { + return actor_id == element.second.sensor_actor_definition()->id; + }); + return find_result; +} + +std::unordered_map::const_iterator +UeWorldPublisher::find_ue_sensor(ActorId actor_id)const +{ + auto find_result = std::find_if(_ue_sensors.begin(), _ue_sensors.end(), + [actor_id](std::pair element) { + return actor_id == element.second.sensor_actor_definition()->id; + }); + return find_result; +} + +carla::ros2::types::Transform UeWorldPublisher::get_transform(ActorId actor_id) { + auto object_it = _objects.find(actor_id); + if (object_it != _objects.end()) { + return object_it->second->Transform(); + } + auto sensor_it = find_ue_sensor(actor_id); + if ( sensor_it != _ue_sensors.end() ) { + return sensor_it->second.transform; + } + return carla::ros2::types::Transform(); +} + + +} // 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..e875da2fe61 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/UeWorldPublisher.h @@ -0,0 +1,277 @@ +// 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/ROS2NameRegistry.h" +#include "carla/ros2/ROS2Session.h" +#include "carla/ros2/publishers/CarlaActorListPublisher.h" +#include "carla/ros2/publishers/CarlaStatusPublisher.h" +#include "carla/ros2/publishers/ClockPublisher.h" +#include "carla/ros2/publishers/WorldInfoPublisher.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/UePublisherBase.h" +#include "carla/ros2/publishers/VehiclePublisher.h" +#include "carla/ros2/publishers/WalkerPublisher.h" +#include "carla/ros2/publishers/WeatherPublisher.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/subscribers/WeatherControlSubscriber.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 + * - environment_objects + * -... + * + */ +class UeWorldPublisher : public UePublisherBase, public std::enable_shared_from_this { +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; + + void Cleanup(); + + /** + * Implement PublisherInterface::Publish interface + */ + bool Publish() override; + + /** + * Implement PublisherInterface::SubscribersConnected() interface + */ + bool SubscribersConnected() const override { + return true; + } + + /** + * Process incoming messages + */ + void ProcessMessages() override; + + /** + * Implement actions on actors removed + */ + void RemoveActor(ActorId actor); + + /** + * Implement UePublisherBase::UpdateSensorDataPreAction() + */ + void UpdateSensorDataPreAction() override; + + /** + * Implement UePublisherBase::UpdateSensorData() + */ + void UpdateSensorData(std::shared_ptr sensor_header, + carla::SharedBufferView buffer_view) override; + /** + * Implement UePublisherBase::UpdateSensorDataPostAction() + */ + void UpdateSensorDataPostAction() override; + + 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); + void AddSensorUe(std::shared_ptr sensor_actor_definition, + carla::ros2::types::ActorSetTransformCallback actor_set_transform_callback = nullptr); + void AddV2XCustomSensorUe(std::shared_ptr sensor_actor_definition, + carla::ros2::types::V2XCustomSendCallback v2x_custom_send_callback); + + void ProcessDataFromUeSensor(carla::streaming::detail::stream_id_type const stream_id, + std::shared_ptr message); + + + uint64_t CurrentFrame() const { + return _frame; + } + carla::ros2::types::Timestamp const &CurrentTimestamp() const { + return _timestamp; + } + + + /* + * @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(); + void UpdateAndPublishEnvironmentObjects(); + + 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::Transform get_transform(ActorId actor_id); + + carla::ros2::types::Timestamp _timestamp{}; + uint64_t _frame{0u}; + carla::sensor::s11n::EpisodeStateSerializer::Header _episode_header; + bool _frame_changed{false}; + 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; + + struct UeSensor { + UeSensor(std::shared_ptr sensor_actor_definition_) + : sensor_actor_record(std::make_shared(sensor_actor_definition_)) {} + std::shared_ptr sensor_actor_definition() { + return std::dynamic_pointer_cast(sensor_actor_record->_actor_name_definition); } + std::shared_ptr sensor_actor_record; + carla::ros2::types::V2XCustomSendCallback v2x_custom_send_callback{nullptr}; + bool publisher_expected{true}; + std::shared_ptr publisher; + std::shared_ptr session; + carla::ros2::types::ActorSetTransformCallback actor_set_transform_callback{nullptr}; + carla::ros2::types::Transform transform; + }; + std::unordered_map _ue_sensors; + + UeSensor* AddSensorUeInternal(std::shared_ptr sensor_actor_definition); + void CreateSensorUePublisher(UeSensor& sensor); + std::unordered_map::iterator find_ue_sensor(ActorId actor_id); + std::unordered_map::const_iterator find_ue_sensor(ActorId actor_id) const; + + std::shared_ptr _domain_participant_impl; + + carla::rpc::RpcServerInterface &_carla_server; + std::shared_ptr _name_registry; + std::shared_ptr _dispatcher; + + // publisher + std::shared_ptr _clock_publisher; + std::shared_ptr _world_info_publisher; + std::shared_ptr _status_publisher; + std::shared_ptr _weather_publisher; + + bool _sensors_changed{false}; + std::shared_ptr _sensor_actor_list_publisher; + + bool _objects_changed{true}; + std::shared_ptr _actor_list_publisher; + std::shared_ptr _objects_publisher; + std::shared_ptr _objects_with_covariance_publisher; + + bool _traffic_lights_changed{true}; + std::shared_ptr _traffic_lights_publisher; + std::shared_ptr _traffic_light_actor_list_publisher; + std::shared_ptr _traffic_light_objects_publisher; + + bool _traffic_signs_changed{true}; + std::shared_ptr _traffic_sign_actor_list_publisher; + std::shared_ptr _traffic_sign_objects_publisher; + + std::shared_ptr _environment_actor_list_publisher; + std::shared_ptr _environment_objects_publisher; + bool _environment_objects_initialized{false}; + + // subscriber + std::shared_ptr _carla_control_subscriber; + std::shared_ptr _weather_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..9017d284cec --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/VehiclePublisher.cpp @@ -0,0 +1,185 @@ +// 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 "VehiclePublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.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, + carla::rpc::RpcServerInterface &carla_server) + : PublisherBaseTransform(std::static_pointer_cast(vehicle_actor_definition), + transform_publisher, TransformPublisher::TransformPublisherMode::MODE_DYNAMIC), + _carla_server(carla_server), + _vehicle_info_publisher(std::make_shared()), + _vehicle_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)) { +} + +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_status_publisher->Init(domain_participant, get_topic_name("vehicle_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() { + bool success = _vehicle_info_publisher->Publish(); + success &= _vehicle_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_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::UpdateSensorDataPreAction() { + // the telemetry data is not transferred by the sensor data stream, + // it has to be requested separately before the sensor data is processed to be able to include it in the sensor data callback processing + if (_vehicle_telemetry_publisher->SubscribersConnected()) { + auto telemetry_data_response = _carla_server.call_get_telemetry_data(_actor_name_definition->id); + if (telemetry_data_response.HasError()) { + carla::log_warning("VehiclePublisher: Failed to get telemetry data for actor id ", + std::to_string(_actor_name_definition->id), ":", telemetry_data_response.GetError().What()); + } + else { + auto const telemetry_data = telemetry_data_response.Get(); + _vehicle_telemetry_publisher->Message().speed(telemetry_data.speed); + _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::CarlaEgoVehicleTelemetryDataWheel 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_telemetry_publisher->SetMessageUpdated(); + } + auto light_state_response = _carla_server.call_get_vehicle_light_state(_actor_name_definition->id); + if (light_state_response.HasError()) { + carla::log_warning("VehiclePublisher: Failed to get vehicle light state for actor id ", + std::to_string(_actor_name_definition->id), ":", light_state_response.GetError().What()); + } else { + auto const light_state = light_state_response.Get(); + _vehicle_telemetry_publisher->Message().light_state_flags(light_state.light_state); + _vehicle_telemetry_publisher->SetMessageUpdated(); + } + } +} + +void VehiclePublisher::UpdateVehicle(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &actor_dynamic_state) { + _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().relative_twist_with_covariance()); + + auto const speed = object->speed().data(); + _vehicle_speed_publisher->Message().data() = speed; + _vehicle_speed_publisher->SetMessageUpdated(); + + // add the timestamp and frame_id to telemetry data + _vehicle_telemetry_publisher->SetMessageHeader(object->Timestamp().time(), "map"); + + _vehicle_status_publisher->SetMessageHeader(object->Timestamp().time(), frame_id()); + _vehicle_status_publisher->Message().velocity() = speed; + _vehicle_status_publisher->Message().acceleration(object->AcceleratedMovement().relative_accel()); + _vehicle_status_publisher->Message().orientation(object->Transform().pose().orientation()); + _vehicle_status_publisher->Message().active_control_type(carla::ros2::types::GetVehicleControlType(actor_dynamic_state)); + _vehicle_status_publisher->Message().last_applied_vehicle_control( + carla::ros2::types::VehicleControl(actor_dynamic_state.state.vehicle_data.GetVehicleControl()) + .carla_vehicle_control()); + _vehicle_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); + + if ( _vehicle_info_publisher->Message().id() != _actor_name_definition->id ) { + // only update the vehicle info message once, as it contains only static information about the vehicle + auto vehicle_actor_definition = std::static_pointer_cast(_actor_name_definition); + _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); + + for (auto wheel : vehicle_actor_definition->vehicle_physics_control.GetWheels()) { + auto wheel_info = carla_msgs::msg::CarlaEgoVehicleInfoWheel(); + 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); + + // convert from cm to m + // TODO: maybe we should change the type of wheel_position from Vector3D to Location in the WheelPhysicsControl, + // as it semantically represents a location, and then we would not have to do this conversion here. + auto wheel_position = carla::geom::Vector3D(wheel.position.x * 1e-2f, wheel.position.y * 1e-2f, wheel.position.z * 1e-2f); + // then make wheel position relative to the vehicle center + object->Transform().GetTransform().InverseTransformPoint(wheel_position); + // then transform it from UE4's left-handed coordinate system to ROS's right-handed coordinate system + wheel_info.position(CoordinateSystemTransform::TransformLinearAxisMsg(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::TransformLinearAxisMsg( + vehicle_actor_definition->vehicle_physics_control.center_of_mass)); + _vehicle_info_publisher->SetMessageUpdated(); + } +} + +} // 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..f6b7367d732 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/VehiclePublisher.h @@ -0,0 +1,79 @@ +// 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/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/CarlaEgoVehicleStatusPubSubTypes.h" +#include "carla_msgs/msg/CarlaEgoVehicleInfoPubSubTypes.h" +#include "carla_msgs/msg/CarlaEgoVehicleTelemetryDataPubSubTypes.h" +#include "nav_msgs/msg/OdometryPubSubTypes.h" +#include "std_msgs/msg/Float32PubSubTypes.h" + +namespace carla { +namespace ros2 { + +using VehicleInfoPublisherImpl = + DdsPublisherImpl; +using EgoVehicleStatusPublisherImpl = + 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, + carla::rpc::RpcServerInterface &carla_server); + 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; + + /** + * Query the not streamed data from the server before processing the sensor data. + */ + void UpdateSensorDataPreAction() override; + + void UpdateVehicle(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &actor_dynamic_state); + +private: + carla::rpc::RpcServerInterface &_carla_server; + std::shared_ptr _vehicle_info_publisher; + std::shared_ptr _vehicle_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..6c02e4191c2 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/WalkerPublisher.cpp @@ -0,0 +1,54 @@ +// 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 "WalkerPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.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, TransformPublisher::TransformPublisherMode::MODE_DYNAMIC), + _walker_odometry_publisher(std::make_shared()), + _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_odometry_publisher->Init(domain_participant, get_topic_name("odometry"), get_topic_qos()) && + _walker_object_publisher->Init(domain_participant) && + _walker_object_with_covariance_publisher->Init(domain_participant); +} + +bool WalkerPublisher::Publish() { + auto success = _walker_odometry_publisher->Publish(); + success &= _walker_object_publisher->Publish(); + success &= _walker_object_with_covariance_publisher->Publish(); + return success; +} + +bool WalkerPublisher::SubscribersConnected() const { + return _walker_odometry_publisher->SubscribersConnected() || + _walker_object_publisher->SubscribersConnected() || + _walker_object_with_covariance_publisher->SubscribersConnected(); +} + +void WalkerPublisher::UpdateWalker(std::shared_ptr &object, + carla::sensor::data::ActorDynamicState const &) { + _walker_odometry_publisher->SetMessageHeader(object->Timestamp().time(), "map"); + _walker_odometry_publisher->Message().child_frame_id(frame_id()); + _walker_odometry_publisher->Message().pose(object->Transform().pose_with_covariance()); + _walker_odometry_publisher->Message().twist(object->AcceleratedMovement().relative_twist_with_covariance()); + + _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..5292a324810 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/WalkerPublisher.h @@ -0,0 +1,53 @@ +// 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/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" +#include "nav_msgs/msg/OdometryPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using WalkerOdometryPublisherImpl = + DdsPublisherImpl; + +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_odometry_publisher; + 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/publishers/WeatherPublisher.cpp b/LibCarla/source/carla/ros2/publishers/WeatherPublisher.cpp new file mode 100644 index 00000000000..9237959d241 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/WeatherPublisher.cpp @@ -0,0 +1,56 @@ +// 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 "WeatherPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" +#include "carla/ros2/types/WeatherParameters.h" + +namespace carla { +namespace ros2 { + +WeatherPublisher::WeatherPublisher(carla::rpc::RpcServerInterface &carla_server) + : PublisherBase(carla::ros2::types::ActorNameDefinition::CreateFromRoleName("weather")), + _impl(std::make_shared()), + _carla_server(carla_server) +{} + +bool WeatherPublisher::Init(std::shared_ptr domain_participant) { + return _impl->Init(domain_participant, get_topic_name(), get_topic_qos().keep_last(1)); +} + +bool WeatherPublisher::Publish() { + return _impl->Publish(); +} + +bool WeatherPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void WeatherPublisher::UpdateSensorDataPreAction() { + // the weather data is not transferred by the sensor data stream, + // it has to be requested separately from the server, + // This should happen within the message processing step, when also other calls are expected + // to ensure the simulation internal data is actually locked and its safe to acceess it. + if (_impl->SubscribersConnected()) { + auto response = _carla_server.call_get_weather_parameters(); + if (response.HasError()) { + carla::log_warning("WeatherPublisher: Failed to get weather parameters " + "from CARLA server: ", response.GetError().What()); + } + else { + carla::ros2::types::WeatherParameters weather_parameters(response.Get()); + auto const new_weather_parameters = weather_parameters.weather_parameters_msg(); + if ( new_weather_parameters != _impl->Message()) + { + // send only out if parameters change + _impl->Message() = new_weather_parameters; + _impl->SetMessageUpdated(); + } + } + } +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/WeatherPublisher.h b/LibCarla/source/carla/ros2/publishers/WeatherPublisher.h new file mode 100644 index 00000000000..afed6bbc384 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/WeatherPublisher.h @@ -0,0 +1,46 @@ +// 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/PublisherBase.h" +#include "carla/rpc/RpcServerInterface.h" +#include "carla_msgs/msg/CarlaWeatherParametersPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using CarlaWeatherParametersPublisherImpl = + DdsPublisherImpl; + +class WeatherPublisher : public PublisherBase { +public: + WeatherPublisher(carla::rpc::RpcServerInterface &carla_server); + virtual ~WeatherPublisher() = 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; + + /** + * Query the not streamed data from the server before processing the sensor data. + */ + void UpdateSensorDataPreAction() override; + +private: + std::shared_ptr _impl; + carla::rpc::RpcServerInterface &_carla_server; +}; +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/WorldInfoPublisher.cpp b/LibCarla/source/carla/ros2/publishers/WorldInfoPublisher.cpp new file mode 100644 index 00000000000..0f701b1564c --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/WorldInfoPublisher.cpp @@ -0,0 +1,44 @@ +// 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 "WorldInfoPublisher.h" + +#include "carla/ros2/impl/DdsPublisherImpl.h" +#include "carla/Version.h" + +namespace carla { +namespace ros2 { + +WorldInfoPublisher::WorldInfoPublisher(carla::rpc::RpcServerInterface &carla_server) + : PublisherBase(carla::ros2::types::ActorNameDefinition::CreateFromRoleName("world_info")), + _impl(std::make_shared()), + _carla_server(carla_server) {} + +bool WorldInfoPublisher::Init(std::shared_ptr domain_participant) { + auto topic_qos = get_topic_qos(); + topic_qos.keep_last(1); + topic_qos.force_synchronous_writer(); + return _impl->InitHistoryPreallocatedWithReallocMemoryMode(domain_participant, get_topic_name(), topic_qos); +} + +bool WorldInfoPublisher::Publish() { + return _impl->Publish(); +} + +bool WorldInfoPublisher::SubscribersConnected() const { + return _impl->SubscribersConnected(); +} + +void WorldInfoPublisher::UpdateSensorDataPreAction() { + if ( _map_updated ) + { + _impl->Message().carla_version(carla::version()); + _impl->Message().map_name(_carla_server.call_get_map_info().Get().name); + _impl->Message().opendrive(_carla_server.call_get_map_data().Get()); + _impl->SetMessageUpdated(); + _map_updated = false; + } +} +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/publishers/WorldInfoPublisher.h b/LibCarla/source/carla/ros2/publishers/WorldInfoPublisher.h new file mode 100644 index 00000000000..a6d0160f102 --- /dev/null +++ b/LibCarla/source/carla/ros2/publishers/WorldInfoPublisher.h @@ -0,0 +1,53 @@ +// 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/PublisherBase.h" +#include "carla/rpc/RpcServerInterface.h" +#include "carla_msgs/msg/CarlaWorldInfoPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using WorldInfoPublisherImpl = DdsPublisherImpl; + +class WorldInfoPublisher : public PublisherBase { +public: + WorldInfoPublisher(carla::rpc::RpcServerInterface &carla_server); + virtual ~WorldInfoPublisher() = 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; + + /** + * Query the not streamed data from the server before processing the sensor data. + */ + void UpdateSensorDataPreAction() override; + + /** + * Indicate that the map has updated and the server should be quieried for map updates. + */ + void SetMapUpdated() { _map_updated=true; } + +private: + std::shared_ptr _impl; + bool _map_updated=false; + carla::rpc::RpcServerInterface &_carla_server; +}; +} // 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..840328ef6ed --- /dev/null +++ b/LibCarla/source/carla/ros2/services/DestroyObjectService.cpp @@ -0,0 +1,34 @@ +// 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 "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->SetSyncServiceCallback(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..d2051f21b12 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/DestroyObjectService.h @@ -0,0 +1,43 @@ +// 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/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..39a4e8224be --- /dev/null +++ b/LibCarla/source/carla/ros2/services/GetAvailableMapsService.cpp @@ -0,0 +1,40 @@ +// 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 "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->SetSyncServiceCallback(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..04082b5095f --- /dev/null +++ b/LibCarla/source/carla/ros2/services/GetAvailableMapsService.h @@ -0,0 +1,43 @@ +// 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/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..ba4ecf5630a --- /dev/null +++ b/LibCarla/source/carla/ros2/services/GetBlueprintsService.cpp @@ -0,0 +1,57 @@ +// 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 "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->SetSyncServiceCallback(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..26007e7451f --- /dev/null +++ b/LibCarla/source/carla/ros2/services/GetBlueprintsService.h @@ -0,0 +1,43 @@ +// 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/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..2129d9a3d48 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/LoadMapService.cpp @@ -0,0 +1,101 @@ +// 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 "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->SetAsyncServiceCallback(std::bind(&LoadMapService::LoadMap, this, std::placeholders::_1)); + return _impl->Init(domain_participant, get_topic_name()); +} + +void LoadMapService::CheckRequest() { + _impl->CheckRequest(); +} + +void LoadMapService::LoadMap( + std::shared_ptr request) { + + bool request_failed = false; + + 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))) { + PendingMapChangeRequest pending_request{request, _episode_begin_count+1}; + _pending_map_change_requests.push_back(pending_request); + 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() ) { + request_failed = true; + _pending_map_change_requests.pop_back(); + error_reason = call_response.GetError().What(); + } + } + else { + request_failed = true; + error_reason = "Map already loaded and no reload requested"; + } + + if (request_failed) { + 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); + carla_msgs::srv::LoadMap_Response response; + response.success(false); + _impl->SendResponse(request, response); + } + else { + /* waiting with the respose for new episode to begin */ + } +} + +void LoadMapService::NotifyBeginEpisode() { + _episode_begin_count++; + + /* process pending map change requests, if any */ + auto pending_request_it = _pending_map_change_requests.begin(); + while (pending_request_it != _pending_map_change_requests.end()) { + if (pending_request_it->required_episode_begin_count <= _episode_begin_count) { + auto request = pending_request_it->request; + log_info("ROS2:LoadMapService(", request->mapname(), + "' with force: ", request->force_reload()?"True":"False", + ", reset_episode_settings: ", request->reset_episode_settings()?"True":"False", + " and map_layers: ", request->map_layers(), + " succeeded"); + carla_msgs::srv::LoadMap_Response response; + response.success(true); + _impl->SendResponse(request, response); + pending_request_it = _pending_map_change_requests.erase(pending_request_it); + } + else { + ++pending_request_it; + } + } +} + +} // 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..84d93aa86e6 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/LoadMapService.h @@ -0,0 +1,50 @@ +// 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/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; + + void NotifyBeginEpisode(); +private: + void LoadMap(std::shared_ptr request); + + std::shared_ptr _impl; + struct PendingMapChangeRequest { + std::shared_ptr request; + uint64_t required_episode_begin_count; + }; + std::deque _pending_map_change_requests; + std::atomic _episode_begin_count{0}; +}; +} // 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..396e647861f --- /dev/null +++ b/LibCarla/source/carla/ros2/services/ServiceBase.h @@ -0,0 +1,41 @@ +// 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/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..ddbcf0a7fbd --- /dev/null +++ b/LibCarla/source/carla/ros2/services/ServiceInterface.h @@ -0,0 +1,44 @@ +// 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 + +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..b9b7f6482bc --- /dev/null +++ b/LibCarla/source/carla/ros2/services/SetEpisodeSettingsService.cpp @@ -0,0 +1,47 @@ +// 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 "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->SetSyncServiceCallback(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.HasError() ) { + log_error("ROS2:SetEpisodeSettings(): failed to apply episode settings: ", + result.GetError().What()); + response.success(false); + } + else { + log_info("ROS2:SetEpisodeSettings(): applied episode settings successful"); + response.success(true); + } + + 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..8109e57050a --- /dev/null +++ b/LibCarla/source/carla/ros2/services/SetEpisodeSettingsService.h @@ -0,0 +1,43 @@ +// 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/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..28032208d80 --- /dev/null +++ b/LibCarla/source/carla/ros2/services/SpawnObjectService.cpp @@ -0,0 +1,129 @@ +// 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 "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->SetSyncServiceCallback(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_debug("ROS2:SpawnObjectService processing request for '", request.blueprint().id(), "' Pose: ", + request.random_pose()?"random":std::to_string(carla::ros2::types::Transform(request.transform()))); + + 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_debug("ROS2:SpawnObjectService processing request. Pose: ", std::to_string(transform), ")"); + 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_debug("ROS2:SpawnObjectService spawn succeeded: ", int32_t(result.Get().id)); + return response; + } + } + }while(retry_count > 0); + + log_error("ROS2:SpawnObjectService failed to retrieve random spawn point after retries"); + response.error_string("SpawnObjectService: failed to retrieve random spawn point after retries"); + response.id(-1); + return response; +} + +} // 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..0a3d3e7601f --- /dev/null +++ b/LibCarla/source/carla/ros2/services/SpawnObjectService.h @@ -0,0 +1,43 @@ +// 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/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..79b22e46362 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) 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 "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("ackermann_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..66d593ae1ae 100644 --- a/LibCarla/source/carla/ros2/subscribers/AckermannControlSubscriber.h +++ b/LibCarla/source/carla/ros2/subscribers/AckermannControlSubscriber.h @@ -5,38 +5,38 @@ #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..239ad1a8e83 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/ActorSetTransformSubscriber.cpp @@ -0,0 +1,35 @@ +// 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 "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("set_transform"), get_topic_qos()); +} + +void ActorSetTransformSubscriber::ProcessMessages() { + while (_impl->HasPublishersConnected() && _impl->HasNewMessage()) { + if (_actor_set_transform_callback != nullptr ) { + carla::ros2::types::Transform transform(_impl->GetMessage()); + _actor_set_transform_callback(transform); + } + else { + carla::log_error("ActorSetTransformSubscriber::ProcessMessages >> set_transform callback is not available!"); + } + } +} + +} // 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..891a55e0cc7 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/ActorSetTransformSubscriber.h @@ -0,0 +1,41 @@ +// 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/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 3b378565aa4..00000000000 --- a/LibCarla/source/carla/ros2/subscribers/BaseSubscriber.h +++ /dev/null @@ -1,50 +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) {} - - virtual ~BaseSubscriber() = default; - - std::string GetBaseTopicName() { return _base_topic_name; } - std::string GetFrameId() { return _frame_id; } - - virtual ROS2CallbackData GetMessage() = 0; - virtual void ProcessMessages(ActorCallback callback) = 0; - - void* GetActor() { return _actor; } - - protected: - void* _actor { nullptr }; - std::string _base_topic_name = ""; - std::string _frame_id = ""; - }; - -} // 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..4a42aae219b --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/CarlaControlSubscriber.cpp @@ -0,0 +1,47 @@ +// 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 "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("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, + carla::rpc::SynchronizationTickMode::FORCE_ENABLE_SYNC); + 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..ab205180e4f --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/CarlaControlSubscriber.h @@ -0,0 +1,46 @@ +// 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/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("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..6e6cc3eba44 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/CarlaSynchronizationWindowSubscriber.cpp @@ -0,0 +1,44 @@ +// 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 "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("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..8572583abaf --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/CarlaSynchronizationWindowSubscriber.h @@ -0,0 +1,49 @@ +// 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/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("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..85879e19c0e --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/SubscriberBase.h @@ -0,0 +1,87 @@ +// 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/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) { + log_debug("SubscriberBase created for topic {}", parent.get_topic_name()); + } + virtual ~SubscriberBase() { + log_debug("SubscriberBase destroyed for topic {}", _parent.get_topic_name()); + }; + + /** + * 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); + } + + carla::streaming::detail::actor_id_type get_actor_id() const { + return _parent.get_actor_id(); + } + +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..2661af79a9c --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/SubscriberBaseSynchronizationClient.h @@ -0,0 +1,85 @@ +// 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/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 c9e489cc135..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 = static_cast(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..6ed2966dfdd --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/SubscriberImplBase.h @@ -0,0 +1,165 @@ +// 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 + +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..2924659dc9f --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/UeV2XCustomSubscriber.cpp @@ -0,0 +1,35 @@ +// 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 "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..5322b9f420d --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/UeV2XCustomSubscriber.h @@ -0,0 +1,41 @@ +// 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/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..03a6cc39baa --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/VehicleControlSubscriber.cpp @@ -0,0 +1,29 @@ +// 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 "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("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..87cc0654c0f --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/VehicleControlSubscriber.h @@ -0,0 +1,41 @@ +// 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/subscribers/SubscriberBase.h" +#include "carla/ros2/types/VehicleActorDefinition.h" +#include "carla_msgs/msg/CarlaEgoVehicleControlPubSubTypes.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..4e8b44c35ea --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/WalkerControlSubscriber.cpp @@ -0,0 +1,29 @@ +// 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 "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("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..eebbd109af5 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/WalkerControlSubscriber.h @@ -0,0 +1,41 @@ +// 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/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/subscribers/WeatherControlSubscriber.cpp b/LibCarla/source/carla/ros2/subscribers/WeatherControlSubscriber.cpp new file mode 100644 index 00000000000..f7e6c49af97 --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/WeatherControlSubscriber.cpp @@ -0,0 +1,30 @@ +// 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 "carla/ros2/subscribers/WeatherControlSubscriber.h" +#include "carla/ros2/types/WeatherParameters.h" +#include "carla/ros2/impl/DdsSubscriberImpl.h" + +namespace carla { +namespace ros2 { + +WeatherControlSubscriber::WeatherControlSubscriber(ROS2NameRecord& parent, + carla::rpc::RpcServerInterface &carla_server) + : SubscriberBase(parent), + _impl(std::make_shared(*this)), + _carla_server(carla_server) {} + +bool WeatherControlSubscriber::Init(std::shared_ptr domain_participant) { + return _impl->Init(domain_participant, get_topic_name("weather_control"), get_topic_qos()); +} + +void WeatherControlSubscriber::ProcessMessages() { + while (_impl->HasPublishersConnected() && _impl->HasNewMessage()) { + carla::ros2::types::WeatherParameters weather_parameter(_impl->GetMessage()); + _carla_server.call_set_weather_parameters(weather_parameter.weather_parameters_rpc()); + } +} + +} // namespace ros2 +} // namespace carla diff --git a/LibCarla/source/carla/ros2/subscribers/WeatherControlSubscriber.h b/LibCarla/source/carla/ros2/subscribers/WeatherControlSubscriber.h new file mode 100644 index 00000000000..bfbb00a5b0c --- /dev/null +++ b/LibCarla/source/carla/ros2/subscribers/WeatherControlSubscriber.h @@ -0,0 +1,41 @@ +// 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/subscribers/SubscriberBase.h" +#include "carla/rpc/RpcServerInterface.h" +#include "carla_msgs/msg/CarlaWeatherParametersPubSubTypes.h" + +namespace carla { +namespace ros2 { + +using WeatherControlSubscriberImpl = + DdsSubscriberImpl; + +class WeatherControlSubscriber : public SubscriberBase { +public: + explicit WeatherControlSubscriber(ROS2NameRecord& parent, + carla::rpc::RpcServerInterface &carla_server); + virtual ~WeatherControlSubscriber() = 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::rpc::RpcServerInterface &_carla_server; +}; +} // 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..c4ba8202084 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/AcceleratedMovement.h @@ -0,0 +1,156 @@ +// 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/Debug.h" +#include "carla/ros2/types/Acceleration.h" +#include "carla/ros2/types/AngularVelocity.h" +#include "carla/ros2/types/Timestamp.h" +#include "carla/geom/Velocity.h" +#include "carla/geom/AngularVelocity.h" +#include "carla/geom/Quaternion.h" +#include "carla/ros2/types/CoordinateSystemTransform.h" +#include "geometry_msgs/msg/AccelWithCovariance.h" +#include "geometry_msgs/msg/TwistWithCovariance.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Track the movement state including the angular acceleration based on speed upates + Allow access for absolute and relative acceleration, velocity and twist in ROS coordinate system + + 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 Update( + carla::geom::Velocity const& linear_velocity, + carla::ros2::types::AngularVelocity const& angular_velocity, + carla::geom::Acceleration const& linear_acceleration, + carla::geom::Quaternion const& quaternion, + Timestamp const& timestamp) { + + _acceleration._carla_linear_acceleration = linear_acceleration; + float delta_seconds = static_cast(timestamp.Stamp() - _timestamp.Stamp()); + if (delta_seconds > 1e-9) { + _acceleration._carla_angular_acceleration_rad = (angular_velocity.GetAngularVelocityRad() - _angular_velocity.GetAngularVelocityRad()) / delta_seconds; + } + + _linear_velocity = linear_velocity; + _angular_velocity = angular_velocity; + _quaternion = quaternion; + _timestamp = timestamp; + } + + Acceleration const & GetAcceleration() const { + return _acceleration; + } + + Acceleration GetRelativeAcceleration() const { + return _acceleration.GetRelative(_quaternion); + } + + geometry_msgs::msg::Accel absolute_accel() const { + return GetAcceleration().accel(); + } + + geometry_msgs::msg::AccelWithCovariance absolute_accel_with_covariance() const { + geometry_msgs::msg::AccelWithCovariance _ros_accel_with_covariance; + _ros_accel_with_covariance.accel(absolute_accel()); + return _ros_accel_with_covariance; + } + + geometry_msgs::msg::Accel relative_accel() const { + return GetRelativeAcceleration().accel(); + } + + geometry_msgs::msg::AccelWithCovariance relative_accel_with_covariance() const { + geometry_msgs::msg::AccelWithCovariance _ros_accel_with_covariance; + _ros_accel_with_covariance.accel(relative_accel()); + return _ros_accel_with_covariance; + } + + carla::geom::Velocity const& LinearVelocity() const { + return _linear_velocity; + } + + geometry_msgs::msg::Vector3 absolute_linear_velocity() const { + return CoordinateSystemTransform::TransformLinearAxisMsg(_linear_velocity);; + } + + carla::geom::Velocity RelativeLinearVelocity() const { + return _quaternion.InverseRotatedVector(_linear_velocity); + } + + geometry_msgs::msg::Vector3 relative_linear_velocity() const { + return CoordinateSystemTransform::TransformLinearAxisMsg(RelativeLinearVelocity());; + } + + carla::ros2::types::AngularVelocity AngularVelocity() const { + return _angular_velocity; + } + + geometry_msgs::msg::Vector3 absolute_angular_velocity() const { + return AngularVelocity().angular_velocity(); + } + + carla::ros2::types::AngularVelocity RelativeAngularVelocity() const { + return AngularVelocity().GetRelative(_quaternion); + } + + geometry_msgs::msg::Vector3 relative_angular_velocity() const { + return RelativeAngularVelocity().angular_velocity(); + } + + geometry_msgs::msg::Twist absolute_twist() const { + geometry_msgs::msg::Twist ros_twist; + ros_twist.linear() = absolute_linear_velocity(); + ros_twist.angular() = absolute_angular_velocity(); + return ros_twist; + } + + geometry_msgs::msg::TwistWithCovariance absolute_twist_with_covariance() const { + geometry_msgs::msg::TwistWithCovariance _ros_twist_with_covariance; + _ros_twist_with_covariance.twist(absolute_twist()); + return _ros_twist_with_covariance; + } + + geometry_msgs::msg::Twist relative_twist() const { + geometry_msgs::msg::Twist ros_twist; + ros_twist.linear() = relative_linear_velocity(); + ros_twist.angular() = relative_angular_velocity(); + return ros_twist; + } + + geometry_msgs::msg::TwistWithCovariance relative_twist_with_covariance() const { + geometry_msgs::msg::TwistWithCovariance _ros_twist_with_covariance; + _ros_twist_with_covariance.twist(relative_twist()); + return _ros_twist_with_covariance; + } + + carla::ros2::types::Timestamp const& Timestamp() const { + return _timestamp; + } + +private: + carla::geom::Velocity _linear_velocity; + carla::ros2::types::AngularVelocity _angular_velocity; + carla::geom::Quaternion _quaternion; + carla::ros2::types::Timestamp _timestamp; + carla::ros2::types::Acceleration _acceleration; +}; +} // 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..00aedab2484 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/Acceleration.h @@ -0,0 +1,83 @@ +// 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/geom/Acceleration.h" +#include "carla/ros2/types/CoordinateSystemTransform.h" +#include "geometry_msgs/msg/Accel.h" +#include "carla/geom/Quaternion.h" + +namespace carla { +namespace ros2 { +namespace types { + +class AcceleratedMovement; + +/** + 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_linear_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()) { + _carla_linear_acceleration = carla_linear_acceleration; + } + ~Acceleration() = default; + Acceleration(const Acceleration&) = default; + Acceleration& operator=(const Acceleration&) = default; + Acceleration(Acceleration&&) = default; + Acceleration& operator=(Acceleration&&) = default; + + + geometry_msgs::msg::Vector3 linear_acceleration() const { + return CoordinateSystemTransform::TransformLinearAxisMsg(_carla_linear_acceleration); + } + + /** + * The resulting ROS angular acceleration as geometry_msgs::msg::Vector3 in ROS coordinates + */ + geometry_msgs::msg::Vector3 angular_acceleration() const { + geometry_msgs::msg::Vector3 angular_acceleration_ros; + angular_acceleration_ros.x() = -_carla_angular_acceleration_rad.x; // -(forward = forward) + angular_acceleration_ros.y() = _carla_angular_acceleration_rad.y; // -( right = -left ) + angular_acceleration_ros.z() = -_carla_angular_acceleration_rad.z; // -( up = up ) + return angular_acceleration_ros; + } + + /** + * The resulting ROS geometry_msgs::msg::Accel + */ + geometry_msgs::msg::Accel accel() const { + geometry_msgs::msg::Accel ros_accel; + ros_accel.linear() = linear_acceleration(); + ros_accel.angular() = angular_acceleration(); + return ros_accel; + } + + /** + * Get the relative acceleration in the reference frame of the provided transform + */ + Acceleration GetRelative(carla::geom::Quaternion const& quat) const { + Acceleration relative_acceleration; + relative_acceleration._carla_linear_acceleration = quat.InverseRotatedVector(_carla_linear_acceleration); + relative_acceleration._carla_angular_acceleration_rad = quat.InverseRotatedVector(_carla_angular_acceleration_rad); + return relative_acceleration; + } + +private: + friend class AcceleratedMovement; + + carla::geom::Acceleration _carla_linear_acceleration; + carla::geom::Acceleration _carla_angular_acceleration_rad; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/AckermannDrive.cpp b/LibCarla/source/carla/ros2/types/AckermannDrive.cpp deleted file mode 100644 index 7e8c0871dd3..00000000000 --- a/LibCarla/source/carla/ros2/types/AckermannDrive.cpp +++ /dev/null @@ -1,341 +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.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 "AckermannDrive.h" -#include - -#include -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 = 0.0; - // float m_steering_angle_velocity - m_steering_angle_velocity = 0.0; - // float m_speed - m_speed = 0.0; - // float m_acceleration - m_acceleration = 0.0; - // float m_jerk - m_jerk = 0.0; - -} - -ackermann_msgs::msg::AckermannDrive::~AckermannDrive() -{ - - - - - -} - -ackermann_msgs::msg::AckermannDrive::AckermannDrive( - const AckermannDrive& x) -{ - m_steering_angle = x.m_steering_angle; - m_steering_angle_velocity = x.m_steering_angle_velocity; - m_speed = x.m_speed; - m_acceleration = x.m_acceleration; - m_jerk = x.m_jerk; -} - -ackermann_msgs::msg::AckermannDrive::AckermannDrive( - AckermannDrive&& x) noexcept -{ - m_steering_angle = x.m_steering_angle; - m_steering_angle_velocity = x.m_steering_angle_velocity; - m_speed = x.m_speed; - m_acceleration = x.m_acceleration; - m_jerk = x.m_jerk; -} - -ackermann_msgs::msg::AckermannDrive& ackermann_msgs::msg::AckermannDrive::operator =( - const AckermannDrive& x) -{ - - m_steering_angle = x.m_steering_angle; - m_steering_angle_velocity = x.m_steering_angle_velocity; - m_speed = x.m_speed; - m_acceleration = x.m_acceleration; - m_jerk = x.m_jerk; - - return *this; -} - -ackermann_msgs::msg::AckermannDrive& ackermann_msgs::msg::AckermannDrive::operator =( - AckermannDrive&& x) noexcept -{ - - m_steering_angle = x.m_steering_angle; - m_steering_angle_velocity = x.m_steering_angle_velocity; - m_speed = x.m_speed; - m_acceleration = x.m_acceleration; - m_jerk = x.m_jerk; - - return *this; -} - -bool ackermann_msgs::msg::AckermannDrive::operator ==( - const AckermannDrive& x) const -{ - - return (m_steering_angle == x.m_steering_angle && m_steering_angle_velocity == x.m_steering_angle_velocity && m_speed == x.m_speed && m_acceleration == x.m_acceleration && m_jerk == x.m_jerk); -} - -bool ackermann_msgs::msg::AckermannDrive::operator !=( - const AckermannDrive& x) const -{ - return !(*this == x); -} - -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 ackermann_msgs::msg::AckermannDrive::getCdrSerializedSize( - const ackermann_msgs::msg::AckermannDrive& 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); - - - - return current_alignment - initial_alignment; -} - -void ackermann_msgs::msg::AckermannDrive::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - - scdr << m_steering_angle; - scdr << m_steering_angle_velocity; - scdr << m_speed; - scdr << m_acceleration; - scdr << m_jerk; - -} - -void ackermann_msgs::msg::AckermannDrive::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - - dcdr >> m_steering_angle; - dcdr >> m_steering_angle_velocity; - dcdr >> m_speed; - dcdr >> m_acceleration; - dcdr >> m_jerk; -} - -/*! - * @brief This function sets a value in member steering_angle - * @param _steering_angle New value for member steering_angle - */ -void ackermann_msgs::msg::AckermannDrive::steering_angle( - float _steering_angle) -{ - m_steering_angle = _steering_angle; -} - -/*! - * @brief This function returns the value of member steering_angle - * @return Value of member steering_angle - */ -float ackermann_msgs::msg::AckermannDrive::steering_angle() const -{ - return m_steering_angle; -} - -/*! - * @brief This function returns a reference to member steering_angle - * @return Reference to member steering_angle - */ -float& ackermann_msgs::msg::AckermannDrive::steering_angle() -{ - return m_steering_angle; -} - -/*! - * @brief This function sets a value in member steering_angle_velocity - * @param _steering_angle_velocity New value for member steering_angle_velocity - */ -void ackermann_msgs::msg::AckermannDrive::steering_angle_velocity( - float _steering_angle_velocity) -{ - m_steering_angle_velocity = _steering_angle_velocity; -} - -/*! - * @brief This function returns the value of member steering_angle_velocity - * @return Value of member steering_angle_velocity - */ -float ackermann_msgs::msg::AckermannDrive::steering_angle_velocity() const -{ - return m_steering_angle_velocity; -} - -/*! - * @brief This function returns a reference to member steering_angle_velocity - * @return Reference to member steering_angle_velocity - */ -float& ackermann_msgs::msg::AckermannDrive::steering_angle_velocity() -{ - return m_steering_angle_velocity; -} - -/*! - * @brief This function sets a value in member speed - * @param _speed New value for member speed - */ -void ackermann_msgs::msg::AckermannDrive::speed( - float _speed) -{ - m_speed = _speed; -} - -/*! - * @brief This function returns the value of member speed - * @return Value of member speed - */ -float ackermann_msgs::msg::AckermannDrive::speed() const -{ - return m_speed; -} - -/*! - * @brief This function returns a reference to member speed - * @return Reference to member speed - */ -float& ackermann_msgs::msg::AckermannDrive::speed() -{ - return m_speed; -} - -/*! - * @brief This function sets a value in member acceleration - * @param _acceleration New value for member acceleration - */ -void ackermann_msgs::msg::AckermannDrive::acceleration( - float _acceleration) -{ - m_acceleration = _acceleration; -} - -/*! - * @brief This function returns the value of member acceleration - * @return Value of member acceleration - */ -float ackermann_msgs::msg::AckermannDrive::acceleration() const -{ - return m_acceleration; -} - -/*! - * @brief This function returns a reference to member acceleration - * @return Reference to member acceleration - */ -float& ackermann_msgs::msg::AckermannDrive::acceleration() -{ - return m_acceleration; -} - -/*! - * @brief This function sets a value in member jerk - * @param _jerk New value for member jerk - */ -void ackermann_msgs::msg::AckermannDrive::jerk( - float _jerk) -{ - m_jerk = _jerk; -} - -/*! - * @brief This function returns the value of member jerk - * @return Value of member jerk - */ -float ackermann_msgs::msg::AckermannDrive::jerk() const -{ - return m_jerk; -} - -/*! - * @brief This function returns a reference to member jerk - * @return Reference to member jerk - */ -float& ackermann_msgs::msg::AckermannDrive::jerk() -{ - return m_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; -} - -bool ackermann_msgs::msg::AckermannDrive::isKeyDefined() -{ - return false; -} - -void ackermann_msgs::msg::AckermannDrive::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} - - - 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.cpp b/LibCarla/source/carla/ros2/types/AckermannDrivePubSubTypes.cpp deleted file mode 100644 index 37ff8e081ec..00000000000 --- a/LibCarla/source/carla/ros2/types/AckermannDrivePubSubTypes.cpp +++ /dev/null @@ -1,178 +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.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - - -#include -#include - -#include "AckermannDrivePubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace ackermann_msgs { - namespace msg { - AckermannDrivePubSubType::AckermannDrivePubSubType() - { - setName("ackermann_msgs::msg::dds_::AckermannDrive_"); - auto type_size = AckermannDrive::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = AckermannDrive::isKeyDefined(); - size_t keyLength = AckermannDrive::getKeyMaxCdrSerializedSize() > 16 ? - AckermannDrive::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - AckermannDrivePubSubType::~AckermannDrivePubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool AckermannDrivePubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - AckermannDrive* 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; - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - p_type->serialize(ser); - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload->length = static_cast(ser.getSerializedDataLength()); - return true; - } - - bool AckermannDrivePubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - // 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 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::Exception& /*exception*/) - { - return false; - } - - return true; - } - - std::function AckermannDrivePubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* AckermannDrivePubSubType::createData() - { - return reinterpret_cast(new AckermannDrive()); - } - - void AckermannDrivePubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool AckermannDrivePubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - AckermannDrive* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - AckermannDrive::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || AckermannDrive::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 ackermann_msgs - diff --git a/LibCarla/source/carla/ros2/types/AckermannDrivePubSubTypes.h b/LibCarla/source/carla/ros2/types/AckermannDrivePubSubTypes.h deleted file mode 100644 index 745cf8db3d8..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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*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/AckermannDriveStamped.cpp b/LibCarla/source/carla/ros2/types/AckermannDriveStamped.cpp deleted file mode 100644 index 3d86e6193f4..00000000000 --- a/LibCarla/source/carla/ros2/types/AckermannDriveStamped.cpp +++ /dev/null @@ -1,241 +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 AckermannDriveStamped.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 "AckermannDriveStamped.h" -#include - -#include -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 - - // ackermann_msgs::msg::AckermannDrive m_drive - - -} - -ackermann_msgs::msg::AckermannDriveStamped::~AckermannDriveStamped() -{ - - -} - -ackermann_msgs::msg::AckermannDriveStamped::AckermannDriveStamped( - const AckermannDriveStamped& x) -{ - m_header = x.m_header; - m_drive = x.m_drive; -} - -ackermann_msgs::msg::AckermannDriveStamped::AckermannDriveStamped( - AckermannDriveStamped&& x) noexcept -{ - m_header = std::move(x.m_header); - m_drive = std::move(x.m_drive); -} - -ackermann_msgs::msg::AckermannDriveStamped& ackermann_msgs::msg::AckermannDriveStamped::operator =( - const AckermannDriveStamped& x) -{ - - m_header = x.m_header; - m_drive = x.m_drive; - - return *this; -} - -ackermann_msgs::msg::AckermannDriveStamped& ackermann_msgs::msg::AckermannDriveStamped::operator =( - AckermannDriveStamped&& x) noexcept -{ - - m_header = std::move(x.m_header); - m_drive = std::move(x.m_drive); - - return *this; -} - -bool ackermann_msgs::msg::AckermannDriveStamped::operator ==( - const AckermannDriveStamped& x) const -{ - - return (m_header == x.m_header && m_drive == x.m_drive); -} - -bool ackermann_msgs::msg::AckermannDriveStamped::operator !=( - const AckermannDriveStamped& x) const -{ - return !(*this == x); -} - -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 ackermann_msgs::msg::AckermannDriveStamped::getCdrSerializedSize( - const ackermann_msgs::msg::AckermannDriveStamped& 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 += ackermann_msgs::msg::AckermannDrive::getCdrSerializedSize(data.drive(), current_alignment); - - return current_alignment - initial_alignment; -} - -void ackermann_msgs::msg::AckermannDriveStamped::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - - scdr << m_header; - scdr << m_drive; - -} - -void ackermann_msgs::msg::AckermannDriveStamped::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - - dcdr >> m_header; - dcdr >> m_drive; -} - -/*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ -void ackermann_msgs::msg::AckermannDriveStamped::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 ackermann_msgs::msg::AckermannDriveStamped::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& ackermann_msgs::msg::AckermannDriveStamped::header() const -{ - return m_header; -} - -/*! - * @brief This function returns a reference to member header - * @return Reference to member header - */ -std_msgs::msg::Header& ackermann_msgs::msg::AckermannDriveStamped::header() -{ - return m_header; -} -/*! - * @brief This function copies the value in member drive - * @param _drive New value to be copied in member drive - */ -void ackermann_msgs::msg::AckermannDriveStamped::drive( - const ackermann_msgs::msg::AckermannDrive& _drive) -{ - m_drive = _drive; -} - -/*! - * @brief This function moves the value in member drive - * @param _drive New value to be moved in member drive - */ -void ackermann_msgs::msg::AckermannDriveStamped::drive( - ackermann_msgs::msg::AckermannDrive&& _drive) -{ - m_drive = std::move(_drive); -} - -/*! - * @brief This function returns a constant reference to member drive - * @return Constant reference to member drive - */ -const ackermann_msgs::msg::AckermannDrive& ackermann_msgs::msg::AckermannDriveStamped::drive() const -{ - return m_drive; -} - -/*! - * @brief This function returns a reference to member drive - * @return Reference to member drive - */ -ackermann_msgs::msg::AckermannDrive& ackermann_msgs::msg::AckermannDriveStamped::drive() -{ - 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; -} - -bool ackermann_msgs::msg::AckermannDriveStamped::isKeyDefined() -{ - return false; -} - -void ackermann_msgs::msg::AckermannDriveStamped::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} - - - diff --git a/LibCarla/source/carla/ros2/types/AckermannDriveStamped.h b/LibCarla/source/carla/ros2/types/AckermannDriveStamped.h deleted file mode 100644 index 5c3427ea345..00000000000 --- a/LibCarla/source/carla/ros2/types/AckermannDriveStamped.h +++ /dev/null @@ -1,248 +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 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 "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(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) noexcept; - - /*! - * @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) noexcept; - - /*! - * @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_ - diff --git a/LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.cpp deleted file mode 100644 index edba64f67ec..00000000000 --- a/LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.cpp +++ /dev/null @@ -1,178 +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 AckermannDriveStampedPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - - -#include -#include - -#include "AckermannDriveStampedPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace ackermann_msgs { - namespace msg { - AckermannDriveStampedPubSubType::AckermannDriveStampedPubSubType() - { - setName("ackermann_msgs::msg::dds_::AckermannDriveStamped_"); - auto type_size = AckermannDriveStamped::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = AckermannDriveStamped::isKeyDefined(); - size_t keyLength = AckermannDriveStamped::getKeyMaxCdrSerializedSize() > 16 ? - AckermannDriveStamped::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - AckermannDriveStampedPubSubType::~AckermannDriveStampedPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool AckermannDriveStampedPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - AckermannDriveStamped* 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; - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - p_type->serialize(ser); - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload->length = static_cast(ser.getSerializedDataLength()); - return true; - } - - bool AckermannDriveStampedPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - // 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 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::Exception& /*exception*/) - { - return false; - } - - return true; - } - - std::function AckermannDriveStampedPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* AckermannDriveStampedPubSubType::createData() - { - return reinterpret_cast(new AckermannDriveStamped()); - } - - void AckermannDriveStampedPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool AckermannDriveStampedPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - AckermannDriveStamped* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - AckermannDriveStamped::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || AckermannDriveStamped::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 ackermann_msgs - diff --git a/LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.h b/LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.h deleted file mode 100644 index 84240bc7cbd..00000000000 --- a/LibCarla/source/carla/ros2/types/AckermannDriveStampedPubSubTypes.h +++ /dev/null @@ -1,113 +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 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" - -#include "AckermannDrivePubSubTypes.h" -#include "HeaderPubSubTypes.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() 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; - - }; - } -} - -#endif // _FAST_DDS_GENERATED_ACKERMANN_MSGS_MSG_ACKERMANNDRIVESTAMPED_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..8bf629dc73f --- /dev/null +++ b/LibCarla/source/carla/ros2/types/ActorDefinition.h @@ -0,0 +1,65 @@ +// 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/geom/BoundingBox.h" +#include "carla/rpc/EnvironmentObject.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 const &bounding_box_) + : ActorNameDefinition(actor_name_definition), bounding_box(bounding_box_) + { + normalize_bounding_box(); + } + + ActorDefinition(const carla::rpc::EnvironmentObject &env_object, bool enabled_for_ros_) + : bounding_box(env_object.bounding_box) { + + id = env_object.id; + type_id = env_object.name; + object_type="environment_object"; + base_type=std::to_string(env_object.type); + enabled_for_ros = enabled_for_ros_; + city_object_label=env_object.type; + + normalize_bounding_box(); + } + + carla::geom::BoundingBox bounding_box; + +private: + void normalize_bounding_box() { + // Unreal Bounding Boxes seem to be not always correct (some were NaN) + if ( std::fpclassify(bounding_box.extent.x) != FP_NORMAL ) + { + bounding_box.extent.x = 0.1f; + bounding_box.extent.y = 0.1f; + bounding_box.extent.z = 0.1f; + } + } +}; + + + +} // 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..9297eb0dc18 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/ActorNameDefinition.cpp @@ -0,0 +1,61 @@ +// 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 "carla/ros2/types/ActorNameDefinition.h" +#include "carla/ros2/types/SensorActorDefinition.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.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); + if ( name_registry != nullptr ) { + actor_info.parent_id(name_registry->ParentActorId(id)); + auto topic_prefix = name_registry->TopicPrefix(id); + if ( topic_prefix.length() >= 3 ) { + // remove "rt/" prefix + topic_prefix = topic_prefix.substr(3); + } + if ( topic_prefix.front() == '/') { + // remove any leading "/" + topic_prefix.erase(topic_prefix.begin()); + } + actor_info.topic_prefix(topic_prefix); + auto sensor_actor_definition = dynamic_cast(this); + if ( sensor_actor_definition != nullptr ) { + if ( id == 0 ) { + // the world and multiple world sensors share the same id + actor_info.frame_id("map"); + } else { + actor_info.frame_id(name_registry->FrameId(id)); + } + } + } else { + // environment objects + actor_info.parent_id(0); + actor_info.topic_prefix("environment/"); + } + for (auto const &attribute: attributes) { + diagnostic_msgs::msg::KeyValue key_value; + key_value.key(attribute.first); + key_value.value(attribute.second); + actor_info.attributes().push_back(key_value); + } + actor_info.city_object_label(static_cast(city_object_label)); + + 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..2d8d6c9ddaa --- /dev/null +++ b/LibCarla/source/carla/ros2/types/ActorNameDefinition.h @@ -0,0 +1,132 @@ +// 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/streaming/detail/Types.h" +#include "carla/rpc/ObjectLabel.h" +#include "carla_msgs/msg/CarlaActorInfo.h" +#include "carla/ros2/ROS2TopicVisibilityDefaultMode.h" + +namespace carla { +namespace ros2 { + +class ROS2NameRegistry; + +namespace types { + +struct ActorNameDefinition { + + ActorNameDefinition() {}; + + ActorNameDefinition(ActorNameDefinition const &other, carla::rpc::CityObjectLabel city_object_label_) + : id(other.id), + type_id(other.type_id), + ros_name(other.ros_name), + role_name(other.role_name), + object_type(other.object_type), + base_type(other.base_type), + enabled_for_ros(other.enabled_for_ros), + publish_tf(other.publish_tf), + frame_id(other.frame_id), + city_object_label(city_object_label_), + attributes(other.attributes) { + } + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + ActorNameDefinition(uint64_t id_, std::string type_id_, FActorDescription const &Description, carla::ros2::ROS2TopicVisibilityDefaultMode const topic_visibility_default_mode) + : id(id_), + type_id(type_id_), + ros_name(std::string(TCHAR_TO_UTF8(*Description.GetAttribute("ros_name").Value))), + role_name(std::string(TCHAR_TO_UTF8(*Description.GetAttribute("role_name").Value))), + object_type(std::string(TCHAR_TO_UTF8(*Description.GetAttribute("object_type").Value))), + base_type(std::string(TCHAR_TO_UTF8(*Description.GetAttribute("base_type").Value))), + enabled_for_ros(false), + frame_id(TCHAR_TO_UTF8(*Description.GetAttribute("ros_frame_id").Value)), + city_object_label(carla::rpc::CityObjectLabel::None) { + + std::string enabled_for_ros_string = TCHAR_TO_UTF8(*Description.GetAttribute("enabled_for_ros").Value); + if ( (enabled_for_ros_string == "") && (topic_visibility_default_mode == carla::ros2::ROS2TopicVisibilityDefaultMode::eOn )) { + enabled_for_ros = true; + } + else { + enabled_for_ros = Description.GetAttribute("enabled_for_ros").Value.ToBool(); + } + std::string ros_publish_tf_string = TCHAR_TO_UTF8(*Description.GetAttribute("ros_publish_tf").Value); + if ( (ros_publish_tf_string == "") && (topic_visibility_default_mode == carla::ros2::ROS2TopicVisibilityDefaultMode::eOn )) { + publish_tf = true; + } + else { + publish_tf = Description.GetAttribute("ros_publish_tf").Value.ToBool(); + } + + for (auto const &ActorVariation: Description.Variations) { + std::string key = TCHAR_TO_UTF8(*ActorVariation.Key); + // filter out some values already stored explicitly + if ((key == "ros_name") + || (key == "role_name") + || (key == "object_type") + || (key == "base_type")) { + continue; + } + std::string value = TCHAR_TO_UTF8(*ActorVariation.Value.Value); + attributes[key] = value; + } } +#endif + + static std::shared_ptr CreateFromRoleName(std::string const &role_name_, + carla::ros2::ROS2TopicVisibilityDefaultMode const topic_visibility_default_mode = carla::ros2::ROS2TopicVisibilityDefaultMode::eOn ) { + auto actor_name_definition = std::make_shared(); + actor_name_definition->role_name = role_name_; + actor_name_definition->base_type = "world"; + actor_name_definition->enabled_for_ros = topic_visibility_default_mode == carla::ros2::ROS2TopicVisibilityDefaultMode::eOn; + return actor_name_definition; + } + + carla_msgs::msg::CarlaActorInfo carla_actor_info(std::shared_ptr name_registry) const; + + virtual ~ActorNameDefinition() = default; + + uint64_t 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}; + bool publish_tf{true}; + std::string frame_id; + carla::rpc::CityObjectLabel city_object_label{carla::rpc::CityObjectLabel::None}; + std::map attributes; + +}; +} // namespace types +} // namespace ros2 +} // namespace carla + +namespace std { + +inline std::string to_string(carla::ros2::types::ActorNameDefinition const &actor_definition) { + std::stringstream str; + str << "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) + << " publish_tf=" << std::to_string(actor_definition.publish_tf) + << " frame_id=" << actor_definition.frame_id; + for (auto const &attribute: actor_definition.attributes) { + str << " " << attribute.first << "=" << attribute.second; + } + str << ")"; + return str.str(); +} + +} // 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..b5d980955db --- /dev/null +++ b/LibCarla/source/carla/ros2/types/AngularVelocity.h @@ -0,0 +1,88 @@ +// 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/geom/AngularVelocity.h" +#include "carla/geom/Math.h" +#include "geometry_msgs/msg/Vector3.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; + + enum class AngularVelocityMode { + DEGREE, + RADIAN + }; + + /** + * carla_AngularVelocity: the carla linear AngularVelocity + */ + AngularVelocity(const carla::geom::AngularVelocity& carla_angular_velocity, AngularVelocityMode mode) { + if ( mode == AngularVelocityMode::RADIAN) { + _carla_angular_velocity_rad.x = carla_angular_velocity.x; + _carla_angular_velocity_rad.y = carla_angular_velocity.y; + _carla_angular_velocity_rad.z = carla_angular_velocity.z; + } else { + _carla_angular_velocity_rad.x = carla::geom::Math::ToRadians(carla_angular_velocity.x); + _carla_angular_velocity_rad.y = carla::geom::Math::ToRadians(carla_angular_velocity.y); + _carla_angular_velocity_rad.z = carla::geom::Math::ToRadians(carla_angular_velocity.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 in ROS coordinates + */ + geometry_msgs::msg::Vector3 angular_velocity() const { + geometry_msgs::msg::Vector3 angular_velocity_ros; + angular_velocity_ros.x() = -_carla_angular_velocity_rad.x; // -(forward = forward) + angular_velocity_ros.y() = _carla_angular_velocity_rad.y; // -( right = -left ) + angular_velocity_ros.z() = -_carla_angular_velocity_rad.z; // -( up = up ) + return angular_velocity_ros; + } + + /** + * The angular velocity in the carla coordinate system in radians per second + */ + carla::geom::AngularVelocity const & GetAngularVelocityRad() const { + return _carla_angular_velocity_rad; + } + + /** + * Get the relative angular velocity in the reference frame of the provided transform + */ + AngularVelocity GetRelative(carla::geom::Quaternion const& quat) const { + AngularVelocity relative_angular_velocity; + relative_angular_velocity._carla_angular_velocity_rad = quat.InverseRotatedVector(_carla_angular_velocity_rad); + return relative_angular_velocity; + } + +private: + carla::geom::AngularVelocity _carla_angular_velocity_rad; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/CameraInfo.cpp b/LibCarla/source/carla/ros2/types/CameraInfo.cpp deleted file mode 100644 index 058e88d3bd3..00000000000 --- a/LibCarla/source/carla/ros2/types/CameraInfo.cpp +++ /dev/null @@ -1,628 +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.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 "CameraInfo.h" -#include - -#include -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; -#define sensor_msgs_msg_RegionOfInterest_max_cdr_typesize 17ULL; -#define std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define builtin_interfaces_msg_Time_max_key_cdr_typesize 0ULL; -#define sensor_msgs_msg_CameraInfo_max_key_cdr_typesize 0ULL; -#define sensor_msgs_msg_RegionOfInterest_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; - -sensor_msgs::msg::CameraInfo::CameraInfo(uint32_t height, uint32_t width, double fov) : -m_height(height), -m_width(width) -{ - // string m_distortion_model - m_distortion_model = "plumb_bob"; - - const double cx = static_cast(m_width) / 2.0; - const double cy = static_cast(m_height) / 2.0; - const double fx = static_cast(m_width) / (2.0 * std::tan(fov) * M_PI / 360.0); - const double fy = fx; - - m_d = { 0.0, 0.0, 0.0, 0.0, 0.0 }; - m_k = {fx, 0.0, cx, 0.0, fy, cy, 0.0, 0.0, 1.0}; - m_r = { 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0 }; - m_p = {fx, 0.0, cx, 0.0, 0.0, fy, cy, 0.0, 0.0, 0.0, 1.0, 0.0}; - - m_binning_x = 0; - m_binning_y = 0; -} - -sensor_msgs::msg::CameraInfo::~CameraInfo() -{ -} - -sensor_msgs::msg::CameraInfo::CameraInfo( - const CameraInfo& x) -{ - m_header = x.m_header; - m_height = x.m_height; - m_width = x.m_width; - m_distortion_model = x.m_distortion_model; - m_d = x.m_d; - m_k = x.m_k; - m_r = x.m_r; - m_p = x.m_p; - m_binning_x = x.m_binning_x; - m_binning_y = x.m_binning_y; - m_roi = x.m_roi; -} - -sensor_msgs::msg::CameraInfo::CameraInfo( - CameraInfo&& x) noexcept -{ - m_header = std::move(x.m_header); - m_height = x.m_height; - m_width = x.m_width; - m_distortion_model = std::move(x.m_distortion_model); - m_d = std::move(x.m_d); - m_k = std::move(x.m_k); - m_r = std::move(x.m_r); - m_p = std::move(x.m_p); - m_binning_x = x.m_binning_x; - m_binning_y = x.m_binning_y; - m_roi = std::move(x.m_roi); -} - -sensor_msgs::msg::CameraInfo& sensor_msgs::msg::CameraInfo::operator =( - const CameraInfo& x) -{ - m_header = x.m_header; - m_height = x.m_height; - m_width = x.m_width; - m_distortion_model = x.m_distortion_model; - m_d = x.m_d; - m_k = x.m_k; - m_r = x.m_r; - m_p = x.m_p; - m_binning_x = x.m_binning_x; - m_binning_y = x.m_binning_y; - m_roi = x.m_roi; - - return *this; -} - -sensor_msgs::msg::CameraInfo& sensor_msgs::msg::CameraInfo::operator =( - CameraInfo&& x) noexcept -{ - m_header = std::move(x.m_header); - m_height = x.m_height; - m_width = x.m_width; - m_distortion_model = std::move(x.m_distortion_model); - m_d = std::move(x.m_d); - m_k = std::move(x.m_k); - m_r = std::move(x.m_r); - m_p = std::move(x.m_p); - m_binning_x = x.m_binning_x; - m_binning_y = x.m_binning_y; - m_roi = std::move(x.m_roi); - - return *this; -} - -bool sensor_msgs::msg::CameraInfo::operator ==( - const CameraInfo& x) const -{ - return (m_header == x.m_header && m_height == x.m_height && m_width == x.m_width && m_distortion_model == x.m_distortion_model && m_d == x.m_d && m_k == x.m_k && m_r == x.m_r && m_p == x.m_p && m_binning_x == x.m_binning_x && m_binning_y == x.m_binning_y && m_roi == x.m_roi); -} - -bool sensor_msgs::msg::CameraInfo::operator !=( - const CameraInfo& x) const -{ - return !(*this == x); -} - -size_t sensor_msgs::msg::CameraInfo::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_CameraInfo_max_cdr_typesize; -} - -size_t sensor_msgs::msg::CameraInfo::getCdrSerializedSize( - const sensor_msgs::msg::CameraInfo& 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) + data.distortion_model().size() + 1; - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - - if (data.D().size() > 0) - { - current_alignment += (data.D().size() * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); - } - - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - - if (data.k().size() > 0) - { - current_alignment += (data.k().size() * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); - } - - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - - if (data.r().size() > 0) - { - current_alignment += (data.r().size() * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); - } - - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4); - - if (data.p().size() > 0) - { - current_alignment += (data.p().size() * 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 += sensor_msgs::msg::RegionOfInterest::getCdrSerializedSize(data.roi(), current_alignment); - - return current_alignment - initial_alignment; -} - -void sensor_msgs::msg::CameraInfo::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_header; - scdr << m_height; - scdr << m_width; - scdr << m_distortion_model.c_str(); - scdr << m_d; - scdr << m_k; - scdr << m_r; - scdr << m_p; - scdr << m_binning_x; - scdr << m_binning_y; - scdr << m_roi; -} - -void sensor_msgs::msg::CameraInfo::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_header; - dcdr >> m_height; - dcdr >> m_width; - dcdr >> m_distortion_model; - dcdr >> m_d; - dcdr >> m_k; - dcdr >> m_r; - dcdr >> m_p; - dcdr >> m_binning_x; - dcdr >> m_binning_y; - dcdr >> m_roi; -} - -/*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ -void sensor_msgs::msg::CameraInfo::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::CameraInfo::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::CameraInfo::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::CameraInfo::header() -{ - return m_header; -} -/*! - * @brief This function sets a value in member height - * @param _height New value for member height - */ -void sensor_msgs::msg::CameraInfo::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::CameraInfo::height() const -{ - return m_height; -} - -/*! - * @brief This function returns a reference to member height - * @return Reference to member height - */ -uint32_t& sensor_msgs::msg::CameraInfo::height() -{ - return m_height; -} - -/*! - * @brief This function sets a value in member width - * @param _width New value for member width - */ -void sensor_msgs::msg::CameraInfo::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::CameraInfo::width() const -{ - return m_width; -} - -/*! - * @brief This function returns a reference to member width - * @return Reference to member width - */ -uint32_t& sensor_msgs::msg::CameraInfo::width() -{ - return m_width; -} - -/*! - * @brief This function copies the value in member distortion_model - * @param _distortion_model New value to be copied in member distortion_model - */ -void sensor_msgs::msg::CameraInfo::distortion_model( - const std::string& _distortion_model) -{ - m_distortion_model = _distortion_model; -} - -/*! - * @brief This function moves the value in member distortion_model - * @param _distortion_model New value to be moved in member distortion_model - */ -void sensor_msgs::msg::CameraInfo::distortion_model( - std::string&& _distortion_model) -{ - m_distortion_model = std::move(_distortion_model); -} - -/*! - * @brief This function returns a constant reference to member distortion_model - * @return Constant reference to member distortion_model - */ -const std::string& sensor_msgs::msg::CameraInfo::distortion_model() const -{ - return m_distortion_model; -} - -/*! - * @brief This function returns a reference to member distortion_model - * @return Reference to member distortion_model - */ -std::string& sensor_msgs::msg::CameraInfo::distortion_model() -{ - return m_distortion_model; -} - -/*! - * @brief This function copies the value in member D - * @param _D New value to be copied in member D - */ -void sensor_msgs::msg::CameraInfo::D( - const std::vector& _D) -{ - m_d = _D; -} - -/*! - * @brief This function moves the value in member D - * @param _D New value to be moved in member D - */ -void sensor_msgs::msg::CameraInfo::D( - std::vector&& _D) -{ - m_d = std::move(_D); -} - -/*! - * @brief This function returns a constant reference to member D - * @return Constant reference to member D - */ -const std::vector& sensor_msgs::msg::CameraInfo::D() const -{ - return m_d; -} - -/*! - * @brief This function returns a reference to member D - * @return Reference to member D - */ -std::vector& sensor_msgs::msg::CameraInfo::D() -{ - return m_d; -} - -/*! - * @brief This function copies the value in member k - * @param _k New value to be copied in member k - */ -void sensor_msgs::msg::CameraInfo::k( - const std::array& _k) -{ - m_k = _k; -} - -/*! - * @brief This function moves the value in member k - * @param _k New value to be moved in member k - */ -void sensor_msgs::msg::CameraInfo::k( - std::array&& _k) -{ - m_k = std::move(_k); -} - -/*! - * @brief This function returns a constant reference to member k - * @return Constant reference to member k - */ -const std::array& sensor_msgs::msg::CameraInfo::k() const -{ - return m_k; -} - -/*! - * @brief This function returns a reference to member k - * @return Reference to member k - */ -std::array& sensor_msgs::msg::CameraInfo::k() -{ - return m_k; -} -/*! - * @brief This function copies the value in member r - * @param _r New value to be copied in member r - */ -void sensor_msgs::msg::CameraInfo::r( - const std::array& _r) -{ - m_r = _r; -} - -/*! - * @brief This function moves the value in member r - * @param _r New value to be moved in member r - */ -void sensor_msgs::msg::CameraInfo::r( - std::array&& _r) -{ - m_r = std::move(_r); -} - -/*! - * @brief This function returns a constant reference to member r - * @return Constant reference to member r - */ -const std::array& sensor_msgs::msg::CameraInfo::r() const -{ - return m_r; -} - -/*! - * @brief This function returns a reference to member r - * @return Reference to member r - */ -std::array& sensor_msgs::msg::CameraInfo::r() -{ - return m_r; -} - -/*! - * @brief This function copies the value in member p - * @param _p New value to be copied in member p - */ -void sensor_msgs::msg::CameraInfo::p( - const std::array& _p) -{ - m_p = _p; -} - -/*! - * @brief This function moves the value in member p - * @param _p New value to be moved in member p - */ -void sensor_msgs::msg::CameraInfo::p( - std::array&& _p) -{ - m_p = std::move(_p); -} - -/*! - * @brief This function returns a constant reference to member p - * @return Constant reference to member p - */ -const std::array& sensor_msgs::msg::CameraInfo::p() const -{ - return m_p; -} - -/*! - * @brief This function returns a reference to member p - * @return Reference to member p - */ -std::array& sensor_msgs::msg::CameraInfo::p() -{ - return m_p; -} - -/*! - * @brief This function sets a value in member binning_x - * @param _binning_x New value for member binning_x - */ -void sensor_msgs::msg::CameraInfo::binning_x( - uint32_t _binning_x) -{ - m_binning_x = _binning_x; -} - -/*! - * @brief This function returns the value of member binning_x - * @return Value of member binning_x - */ -uint32_t sensor_msgs::msg::CameraInfo::binning_x() const -{ - return m_binning_x; -} - -/*! - * @brief This function returns a reference to member binning_x - * @return Reference to member binning_x - */ -uint32_t& sensor_msgs::msg::CameraInfo::binning_x() -{ - return m_binning_x; -} - -/*! - * @brief This function sets a value in member binning_y - * @param _binning_y New value for member binning_y - */ -void sensor_msgs::msg::CameraInfo::binning_y( - uint32_t _binning_y) -{ - m_binning_y = _binning_y; -} - -/*! - * @brief This function returns the value of member binning_y - * @return Value of member binning_y - */ -uint32_t sensor_msgs::msg::CameraInfo::binning_y() const -{ - return m_binning_y; -} - -/*! - * @brief This function returns a reference to member binning_y - * @return Reference to member binning_y - */ -uint32_t& sensor_msgs::msg::CameraInfo::binning_y() -{ - return m_binning_y; -} - -/*! - * @brief This function copies the value in member roi - * @param _roi New value to be copied in member roi - */ -void sensor_msgs::msg::CameraInfo::roi( - const sensor_msgs::msg::RegionOfInterest& _roi) -{ - m_roi = _roi; -} - -/*! - * @brief This function moves the value in member roi - * @param _roi New value to be moved in member roi - */ -void sensor_msgs::msg::CameraInfo::roi( - sensor_msgs::msg::RegionOfInterest&& _roi) -{ - m_roi = std::move(_roi); -} - -/*! - * @brief This function returns a constant reference to member roi - * @return Constant reference to member roi - */ -const sensor_msgs::msg::RegionOfInterest& sensor_msgs::msg::CameraInfo::roi() const -{ - return m_roi; -} - -/*! - * @brief This function returns a reference to member roi - * @return Reference to member roi - */ -sensor_msgs::msg::RegionOfInterest& sensor_msgs::msg::CameraInfo::roi() -{ - return m_roi; -} - -size_t sensor_msgs::msg::CameraInfo::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_CameraInfo_max_key_cdr_typesize; -} - -bool sensor_msgs::msg::CameraInfo::isKeyDefined() -{ - return false; -} - -void sensor_msgs::msg::CameraInfo::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} 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/CameraInfoPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/CameraInfoPubSubTypes.cpp deleted file mode 100644 index 04ce6e70226..00000000000 --- a/LibCarla/source/carla/ros2/types/CameraInfoPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 CameraInfoPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "CameraInfoPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace sensor_msgs { - namespace msg { - CameraInfoPubSubType::CameraInfoPubSubType() - { - setName("sensor_msgs::msg::dds_::CameraInfo_"); - auto type_size = CameraInfo::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = CameraInfo::isKeyDefined(); - size_t keyLength = CameraInfo::getKeyMaxCdrSerializedSize() > 16 ? - CameraInfo::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - CameraInfoPubSubType::~CameraInfoPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool CameraInfoPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - CameraInfo* 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; - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - p_type->serialize(ser); - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload->length = static_cast(ser.getSerializedDataLength()); - return true; - } - - bool CameraInfoPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - // Convert DATA to pointer of your type - CameraInfo* 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::Exception& /*exception*/) - { - return false; - } - - return true; - } - - std::function CameraInfoPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* CameraInfoPubSubType::createData() - { - return reinterpret_cast(new CameraInfo()); - } - - void CameraInfoPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool CameraInfoPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - CameraInfo* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - CameraInfo::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || CameraInfo::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/types/CameraInfoPubSubTypes.h b/LibCarla/source/carla/ros2/types/CameraInfoPubSubTypes.h deleted file mode 100644 index fe7764ab98e..00000000000 --- a/LibCarla/source/carla/ros2/types/CameraInfoPubSubTypes.h +++ /dev/null @@ -1,108 +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 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 "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; - }; - } -} - -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_CAMERAINFO_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/CarlaCollisionEvent.cpp b/LibCarla/source/carla/ros2/types/CarlaCollisionEvent.cpp deleted file mode 100644 index 4d01b7d78f8..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaCollisionEvent.cpp +++ /dev/null @@ -1,261 +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 CarlaCarlaCollisionEvent.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 "CarlaCollisionEvent.h" -#include - -#include -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_other_actor_id = 0; - // geometry_msgs::msg::Vector3 m_normal_impulse -} - -carla_msgs::msg::CarlaCollisionEvent::~CarlaCollisionEvent() -{ -} - -carla_msgs::msg::CarlaCollisionEvent::CarlaCollisionEvent( - const CarlaCollisionEvent& x) -{ - m_header = x.m_header; - m_other_actor_id = x.m_other_actor_id; - m_normal_impulse = x.m_normal_impulse; -} - -carla_msgs::msg::CarlaCollisionEvent::CarlaCollisionEvent( - CarlaCollisionEvent&& x) noexcept -{ - 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); -} - -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; - - return *this; -} - -carla_msgs::msg::CarlaCollisionEvent& carla_msgs::msg::CarlaCollisionEvent::operator =( - CarlaCollisionEvent&& x) noexcept -{ - 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); - - return *this; -} - -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); -} - -bool carla_msgs::msg::CarlaCollisionEvent::operator !=( - const CarlaCollisionEvent& x) const -{ - return !(*this == x); -} - -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 carla_msgs::msg::CarlaCollisionEvent::getCdrSerializedSize( - const carla_msgs::msg::CarlaCollisionEvent& 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 += 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; -} - -/*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ -void carla_msgs::msg::CarlaCollisionEvent::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::CarlaCollisionEvent::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::CarlaCollisionEvent::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::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 - */ -void carla_msgs::msg::CarlaCollisionEvent::other_actor_id( - uint32_t _other_actor_id) -{ - m_other_actor_id = _other_actor_id; -} - -/*! - * @brief This function returns the value of member other_actor_id - * @return Value of member other_actor_id - */ -uint32_t carla_msgs::msg::CarlaCollisionEvent::other_actor_id() const -{ - return m_other_actor_id; -} - -/*! - * @brief This function returns a reference to member other_actor_id - * @return Reference to member other_actor_id - */ -uint32_t& carla_msgs::msg::CarlaCollisionEvent::other_actor_id() -{ - return m_other_actor_id; -} - -/*! - * @brief This function copies the value in member normal_impulse - * @param _normal_impulse New value to be copied in member normal_impulse - */ -void carla_msgs::msg::CarlaCollisionEvent::normal_impulse( - const geometry_msgs::msg::Vector3& _normal_impulse) -{ - m_normal_impulse = _normal_impulse; -} - -/*! - * @brief This function moves the value in member normal_impulse - * @param _normal_impulse New value to be moved in member normal_impulse - */ -void carla_msgs::msg::CarlaCollisionEvent::normal_impulse( - geometry_msgs::msg::Vector3&& _normal_impulse) -{ - m_normal_impulse = std::move(_normal_impulse); -} - -/*! - * @brief This function returns a constant reference to member normal_impulse - * @return Constant reference to member normal_impulse - */ -const geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaCollisionEvent::normal_impulse() const -{ - return m_normal_impulse; -} - -/*! - * @brief This function returns a reference to member normal_impulse - * @return Reference to member normal_impulse - */ -geometry_msgs::msg::Vector3& carla_msgs::msg::CarlaCollisionEvent::normal_impulse() -{ - return m_normal_impulse; -} - -size_t carla_msgs::msg::CarlaCollisionEvent::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return carla_msgs_msg_CarlaCollisionEvent_max_key_cdr_typesize; -} - -bool carla_msgs::msg::CarlaCollisionEvent::isKeyDefined() -{ - return false; -} - -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/types/CarlaCollisionEvent.h deleted file mode 100644 index 6aacc077a70..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaCollisionEvent.h +++ /dev/null @@ -1,262 +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 CarlaCollisionEvent.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_CARLACOLLISIONEVENT_H_ -#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_H_ - -#include "Vector3.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(CarlaCollisionEvent_SOURCE) -#define CarlaCollisionEvent_DllAPI __declspec( dllexport ) -#else -#define CarlaCollisionEvent_DllAPI __declspec( dllimport ) -#endif // CarlaCollisionEvent_SOURCE -#else -#define CarlaCollisionEvent_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define CarlaCollisionEvent_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - - -namespace carla_msgs { - namespace msg { - /*! - * @brief This class represents the structure CarlaCollisionEvent defined by the user in the IDL file. - * @ingroup CARLACOLLISIONEVENT - */ - class CarlaCollisionEvent - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport CarlaCollisionEvent(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~CarlaCollisionEvent(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object carla_msgs::msg::CarlaCollisionEvent that will be copied. - */ - eProsima_user_DllExport CarlaCollisionEvent( - const CarlaCollisionEvent& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object carla_msgs::msg::CarlaCollisionEvent that will be copied. - */ - eProsima_user_DllExport CarlaCollisionEvent( - CarlaCollisionEvent&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object carla_msgs::msg::CarlaCollisionEvent that will be copied. - */ - eProsima_user_DllExport CarlaCollisionEvent& operator =( - const CarlaCollisionEvent& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object carla_msgs::msg::CarlaCollisionEvent that will be copied. - */ - eProsima_user_DllExport CarlaCollisionEvent& operator =( - CarlaCollisionEvent&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x carla_msgs::msg::CarlaCollisionEvent object to compare. - */ - eProsima_user_DllExport bool operator ==( - const CarlaCollisionEvent& x) const; - - /*! - * @brief Comparison operator. - * @param x carla_msgs::msg::CarlaCollisionEvent object to compare. - */ - eProsima_user_DllExport bool operator !=( - const CarlaCollisionEvent& 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 other_actor_id - * @param _other_actor_id New value for member other_actor_id - */ - eProsima_user_DllExport void other_actor_id( - uint32_t _other_actor_id); - - /*! - * @brief This function returns the value of member other_actor_id - * @return Value of member other_actor_id - */ - eProsima_user_DllExport uint32_t other_actor_id() const; - - /*! - * @brief This function returns a reference to member other_actor_id - * @return Reference to member other_actor_id - */ - eProsima_user_DllExport uint32_t& other_actor_id(); - - /*! - * @brief This function copies the value in member normal_impulse - * @param _normal_impulse New value to be copied in member normal_impulse - */ - eProsima_user_DllExport void normal_impulse( - const geometry_msgs::msg::Vector3& _normal_impulse); - - /*! - * @brief This function moves the value in member normal_impulse - * @param _normal_impulse New value to be moved in member normal_impulse - */ - eProsima_user_DllExport void normal_impulse( - geometry_msgs::msg::Vector3&& _normal_impulse); - - /*! - * @brief This function returns a constant reference to member normal_impulse - * @return Constant reference to member normal_impulse - */ - eProsima_user_DllExport const geometry_msgs::msg::Vector3& normal_impulse() const; - - /*! - * @brief This function returns a reference to member normal_impulse - * @return Reference to member normal_impulse - */ - 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. - */ - 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::CarlaCollisionEvent& 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_other_actor_id; - geometry_msgs::msg::Vector3 m_normal_impulse; - }; - } // namespace msg -} // namespace carla_msgs - -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_H_ diff --git a/LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.cpp deleted file mode 100644 index c1822eb2b68..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 CarlaCollisionEventPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "CarlaCollisionEventPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace carla_msgs { - namespace msg { - CarlaCollisionEventPubSubType::CarlaCollisionEventPubSubType() - { - setName("carla_msgs::msg::dds_::CarlaCollisionEvent_"); - auto type_size = CarlaCollisionEvent::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = CarlaCollisionEvent::isKeyDefined(); - size_t keyLength = CarlaCollisionEvent::getKeyMaxCdrSerializedSize() > 16 ? - CarlaCollisionEvent::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - CarlaCollisionEventPubSubType::~CarlaCollisionEventPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool CarlaCollisionEventPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - CarlaCollisionEvent* 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 CarlaCollisionEventPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //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 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; - } - - std::function CarlaCollisionEventPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* CarlaCollisionEventPubSubType::createData() - { - return reinterpret_cast(new CarlaCollisionEvent()); - } - - void CarlaCollisionEventPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool CarlaCollisionEventPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - CarlaCollisionEvent* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - CarlaCollisionEvent::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || CarlaCollisionEvent::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/CarlaCollisionEventPubSubTypes.h b/LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.h deleted file mode 100644 index d532d8e851e..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaCollisionEventPubSubTypes.h +++ /dev/null @@ -1,111 +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 CarlaCollisionEventPubSubTypes.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_CARLACOLLISIONEVENT_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_PUBSUBTYPES_H_ - -#include -#include - -#include "CarlaCollisionEvent.h" -#include "Vector3PubSubTypes.h" -#include "HeaderPubSubTypes.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated CarlaCollisionEvent 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 CarlaCollisionEvent defined by the user in the IDL file. - * @ingroup CARLACOLLISIONEVENT - */ - class CarlaCollisionEventPubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef CarlaCollisionEvent type; - - eProsima_user_DllExport CarlaCollisionEventPubSubType(); - - eProsima_user_DllExport virtual ~CarlaCollisionEventPubSubType() 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; - - }; - } -} - -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLACOLLISIONEVENT_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.cpp b/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.cpp deleted file mode 100644 index 2c1eb165ef5..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.cpp +++ /dev/null @@ -1,435 +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 CarlaEgoCarlaEgoVehicleControl.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 "CarlaEgoVehicleControl.h" -#include - -#include -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() -{ - // std_msgs::msg::Header m_header - - // float m_throttle - m_throttle = 0.0; - // float m_steer - m_steer = 0.0; - // float m_brake - m_brake = 0.0; - // boolean m_hand_brake - m_hand_brake = false; - // boolean m_reverse - m_reverse = false; - // long m_gear - m_gear = 0; - // boolean m_manual_gear_shift - m_manual_gear_shift = false; - -} - -carla_msgs::msg::CarlaEgoVehicleControl::~CarlaEgoVehicleControl() -{ -} - -carla_msgs::msg::CarlaEgoVehicleControl::CarlaEgoVehicleControl( - const CarlaEgoVehicleControl& x) -{ - 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; -} - -carla_msgs::msg::CarlaEgoVehicleControl::CarlaEgoVehicleControl( - CarlaEgoVehicleControl&& x) noexcept -{ - m_header = std::move(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; -} - -carla_msgs::msg::CarlaEgoVehicleControl& carla_msgs::msg::CarlaEgoVehicleControl::operator =( - const CarlaEgoVehicleControl& x) -{ - 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 *this; -} - -carla_msgs::msg::CarlaEgoVehicleControl& carla_msgs::msg::CarlaEgoVehicleControl::operator =( - CarlaEgoVehicleControl&& x) noexcept -{ - m_header = std::move(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 *this; -} - -bool carla_msgs::msg::CarlaEgoVehicleControl::operator ==( - const CarlaEgoVehicleControl& 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); -} - -bool carla_msgs::msg::CarlaEgoVehicleControl::operator !=( - const CarlaEgoVehicleControl& x) const -{ - return !(*this == x); -} - -size_t carla_msgs::msg::CarlaEgoVehicleControl::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return carla_msgs_msg_CarlaEgoVehicleControl_max_cdr_typesize; -} - -size_t carla_msgs::msg::CarlaEgoVehicleControl::getCdrSerializedSize( - const carla_msgs::msg::CarlaEgoVehicleControl& 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); - 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); - return current_alignment - initial_alignment; -} - -void carla_msgs::msg::CarlaEgoVehicleControl::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_header; - scdr << m_throttle; - scdr << m_steer; - scdr << m_brake; - scdr << m_hand_brake; - scdr << m_reverse; - scdr << m_gear; - scdr << m_manual_gear_shift; -} - -void carla_msgs::msg::CarlaEgoVehicleControl::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_header; - dcdr >> m_throttle; - dcdr >> m_steer; - dcdr >> m_brake; - dcdr >> m_hand_brake; - dcdr >> m_reverse; - dcdr >> m_gear; - dcdr >> m_manual_gear_shift; -} - -/*! - * @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( - 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::CarlaEgoVehicleControl::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::CarlaEgoVehicleControl::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::CarlaEgoVehicleControl::header() -{ - return m_header; -} -/*! - * @brief This function sets a value in member throttle - * @param _throttle New value for member throttle - */ -void carla_msgs::msg::CarlaEgoVehicleControl::throttle( - float _throttle) -{ - m_throttle = _throttle; -} - -/*! - * @brief This function returns the value of member throttle - * @return Value of member throttle - */ -float carla_msgs::msg::CarlaEgoVehicleControl::throttle() const -{ - return m_throttle; -} - -/*! - * @brief This function returns a reference to member throttle - * @return Reference to member throttle - */ -float& carla_msgs::msg::CarlaEgoVehicleControl::throttle() -{ - return m_throttle; -} - -/*! - * @brief This function sets a value in member steer - * @param _steer New value for member steer - */ -void carla_msgs::msg::CarlaEgoVehicleControl::steer( - float _steer) -{ - m_steer = _steer; -} - -/*! - * @brief This function returns the value of member steer - * @return Value of member steer - */ -float carla_msgs::msg::CarlaEgoVehicleControl::steer() const -{ - return m_steer; -} - -/*! - * @brief This function returns a reference to member steer - * @return Reference to member steer - */ -float& carla_msgs::msg::CarlaEgoVehicleControl::steer() -{ - return m_steer; -} - -/*! - * @brief This function sets a value in member brake - * @param _brake New value for member brake - */ -void carla_msgs::msg::CarlaEgoVehicleControl::brake( - float _brake) -{ - m_brake = _brake; -} - -/*! - * @brief This function returns the value of member brake - * @return Value of member brake - */ -float carla_msgs::msg::CarlaEgoVehicleControl::brake() const -{ - return m_brake; -} - -/*! - * @brief This function returns a reference to member brake - * @return Reference to member brake - */ -float& carla_msgs::msg::CarlaEgoVehicleControl::brake() -{ - return m_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( - bool _hand_brake) -{ - m_hand_brake = _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 -{ - return m_hand_brake; -} - -/*! - * @brief This function returns a reference to member hand_brake - * @return Reference to member hand_brake - */ -bool& carla_msgs::msg::CarlaEgoVehicleControl::hand_brake() -{ - return m_hand_brake; -} - -/*! - * @brief This function sets a value in member reverse - * @param _reverse New value for member reverse - */ -void carla_msgs::msg::CarlaEgoVehicleControl::reverse( - bool _reverse) -{ - m_reverse = _reverse; -} - -/*! - * @brief This function returns the value of member reverse - * @return Value of member reverse - */ -bool carla_msgs::msg::CarlaEgoVehicleControl::reverse() const -{ - return m_reverse; -} - -/*! - * @brief This function returns a reference to member reverse - * @return Reference to member reverse - */ -bool& carla_msgs::msg::CarlaEgoVehicleControl::reverse() -{ - return m_reverse; -} - -/*! - * @brief This function sets a value in member gear - * @param _gear New value for member gear - */ -void carla_msgs::msg::CarlaEgoVehicleControl::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::CarlaEgoVehicleControl::gear() const -{ - return m_gear; -} - -/*! - * @brief This function returns a reference to member gear - * @return Reference to member gear - */ -int32_t& carla_msgs::msg::CarlaEgoVehicleControl::gear() -{ - return m_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( - bool _manual_gear_shift) -{ - m_manual_gear_shift = _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 -{ - return m_manual_gear_shift; -} - -/*! - * @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() -{ - return m_manual_gear_shift; -} - -size_t carla_msgs::msg::CarlaEgoVehicleControl::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return carla_msgs_msg_CarlaEgoVehicleControl_max_key_cdr_typesize; -} - -bool carla_msgs::msg::CarlaEgoVehicleControl::isKeyDefined() -{ - return false; -} - -void carla_msgs::msg::CarlaEgoVehicleControl::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.h b/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.h deleted file mode 100644 index f941d5dcb41..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControl.h +++ /dev/null @@ -1,354 +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 CarlaEgoCarlaEgoVehicleControl.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_ - -#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(CarlaEgoCarlaEgoVehicleControl_SOURCE) -#define CarlaEgoCarlaEgoVehicleControl_DllAPI __declspec( dllexport ) -#else -#define CarlaEgoCarlaEgoVehicleControl_DllAPI __declspec( dllimport ) -#endif // CarlaEgoCarlaEgoVehicleControl_SOURCE -#else -#define CarlaEgoCarlaEgoVehicleControl_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define CarlaEgoCarlaEgoVehicleControl_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -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 - */ - class CarlaEgoVehicleControl - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport CarlaEgoVehicleControl(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~CarlaEgoVehicleControl(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. - */ - eProsima_user_DllExport CarlaEgoVehicleControl( - const CarlaEgoVehicleControl& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. - */ - eProsima_user_DllExport CarlaEgoVehicleControl( - CarlaEgoVehicleControl&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. - */ - eProsima_user_DllExport CarlaEgoVehicleControl& operator =( - const CarlaEgoVehicleControl& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object carla_msgs::msg::CarlaEgoVehicleControl that will be copied. - */ - eProsima_user_DllExport CarlaEgoVehicleControl& operator =( - CarlaEgoVehicleControl&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x carla_msgs::msg::CarlaEgoVehicleControl object to compare. - */ - eProsima_user_DllExport bool operator ==( - const CarlaEgoVehicleControl& x) const; - - /*! - * @brief Comparison operator. - * @param x carla_msgs::msg::CarlaEgoVehicleControl object to compare. - */ - eProsima_user_DllExport bool operator !=( - const CarlaEgoVehicleControl& 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 throttle - * @param _throttle New value for member throttle - */ - eProsima_user_DllExport void throttle( - float _throttle); - - /*! - * @brief This function returns the value of member throttle - * @return Value of member throttle - */ - eProsima_user_DllExport float throttle() const; - - /*! - * @brief This function returns a reference to member throttle - * @return Reference to member throttle - */ - eProsima_user_DllExport float& throttle(); - - /*! - * @brief This function sets a value in member steer - * @param _steer New value for member steer - */ - eProsima_user_DllExport void steer( - float _steer); - - /*! - * @brief This function returns the value of member steer - * @return Value of member steer - */ - eProsima_user_DllExport float steer() const; - - /*! - * @brief This function returns a reference to member steer - * @return Reference to member steer - */ - eProsima_user_DllExport float& steer(); - - /*! - * @brief This function sets a value in member brake - * @param _brake New value for member brake - */ - eProsima_user_DllExport void brake( - float _brake); - - /*! - * @brief This function returns the value of member brake - * @return Value of member brake - */ - eProsima_user_DllExport float brake() const; - - /*! - * @brief This function returns a reference to member brake - * @return Reference to member brake - */ - eProsima_user_DllExport float& brake(); - - /*! - * @brief This function sets a value in member hand_brake - * @param _hand_brake New value for member hand_brake - */ - eProsima_user_DllExport void hand_brake( - bool _hand_brake); - - /*! - * @brief This function returns the value of member hand_brake - * @return Value of member hand_brake - */ - eProsima_user_DllExport bool hand_brake() const; - - /*! - * @brief This function returns a reference to member hand_brake - * @return Reference to member hand_brake - */ - eProsima_user_DllExport bool& hand_brake(); - - /*! - * @brief This function sets a value in member reverse - * @param _reverse New value for member reverse - */ - eProsima_user_DllExport void reverse( - bool _reverse); - - /*! - * @brief This function returns the value of member reverse - * @return Value of member reverse - */ - eProsima_user_DllExport bool reverse() const; - - /*! - * @brief This function returns a reference to member reverse - * @return Reference to member reverse - */ - eProsima_user_DllExport bool& reverse(); - - /*! - * @brief This function sets a value in member gear - * @param _gear New value for member gear - */ - eProsima_user_DllExport void gear( - int32_t _gear); - - /*! - * @brief This function returns the value of member gear - * @return Value of member gear - */ - eProsima_user_DllExport int32_t gear() const; - - /*! - * @brief This function returns a reference to member gear - * @return Reference to member gear - */ - eProsima_user_DllExport int32_t& gear(); - - /*! - * @brief This function sets a value in member manual_gear_shift - * @param _manual_gear_shift New value for member manual_gear_shift - */ - eProsima_user_DllExport void manual_gear_shift( - bool _manual_gear_shift); - - /*! - * @brief This function returns the value of member manual_gear_shift - * @return Value of member manual_gear_shift - */ - eProsima_user_DllExport bool manual_gear_shift() const; - - /*! - * @brief This function returns a reference to member manual_gear_shift - * @return Reference to member manual_gear_shift - */ - 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. - */ - 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::CarlaEgoVehicleControl& 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; - float m_throttle; - float m_steer; - float m_brake; - bool m_hand_brake; - bool m_reverse; - int32_t m_gear; - bool m_manual_gear_shift; - - }; - } // namespace msg -} // namespace carla_msgs - -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOCarlaEgoVehicleControl_H_ diff --git a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.cpp deleted file mode 100644 index c5ff5216967..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 CarlaEgoCarlaEgoVehicleControlPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "CarlaEgoVehicleControlPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace carla_msgs { - namespace msg { - CarlaEgoVehicleControlPubSubType::CarlaEgoVehicleControlPubSubType() - { - setName("carla_msgs::msg::dds_::CarlaEgoVehicleControl_"); - auto type_size = CarlaEgoVehicleControl::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_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - CarlaEgoVehicleControlPubSubType::~CarlaEgoVehicleControlPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool CarlaEgoVehicleControlPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - CarlaEgoVehicleControl* 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 CarlaEgoVehicleControlPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - CarlaEgoVehicleControl* 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; - } - - std::function CarlaEgoVehicleControlPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* CarlaEgoVehicleControlPubSubType::createData() - { - return reinterpret_cast(new CarlaEgoVehicleControl()); - } - - void CarlaEgoVehicleControlPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool CarlaEgoVehicleControlPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - CarlaEgoVehicleControl* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - CarlaEgoVehicleControl::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) - { - 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/types/CarlaEgoVehicleControlPubSubTypes.h deleted file mode 100644 index 4d064e66a79..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaEgoVehicleControlPubSubTypes.h +++ /dev/null @@ -1,107 +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 CarlaEgoCarlaEgoVehicleControlPubSubTypes.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_ - -#include -#include - -#include "CarlaEgoVehicleControl.h" - -#include "HeaderPubSubTypes.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. -#endif // GEN_API_VER - -namespace carla_msgs -{ - namespace msg - { - /*! - * @brief This class represents the TopicDataType of the type CarlaEgoVehicleControl defined by the user in the IDL file. - * @ingroup CarlaEgoVehicleControl - */ - class CarlaEgoVehicleControlPubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef CarlaEgoVehicleControl type; - - eProsima_user_DllExport CarlaEgoVehicleControlPubSubType(); - - eProsima_user_DllExport virtual ~CarlaEgoVehicleControlPubSubType() 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; - }; - } -} - -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLAEGOCarlaEgoVehicleControl_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/CarlaLineInvasion.cpp b/LibCarla/source/carla/ros2/types/CarlaLineInvasion.cpp deleted file mode 100644 index ce483598762..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaLineInvasion.cpp +++ /dev/null @@ -1,225 +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 CarlaLineInvasion.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 "CarlaLineInvasion.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define carla_msgs_msg_std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define carla_msgs_msg_LaneInvasionEvent_max_cdr_typesize 672ULL; -#define carla_msgs_msg_std_msgs_msg_Time_max_cdr_typesize 8ULL; -#define carla_msgs_msg_std_msgs_msg_Header_max_key_cdr_typesize 0ULL; -#define carla_msgs_msg_LaneInvasionEvent_max_key_cdr_typesize 0ULL; -#define carla_msgs_msg_std_msgs_msg_Time_max_key_cdr_typesize 0ULL; - -carla_msgs::msg::LaneInvasionEvent::LaneInvasionEvent() -{ -} - -carla_msgs::msg::LaneInvasionEvent::~LaneInvasionEvent() -{ -} - -carla_msgs::msg::LaneInvasionEvent::LaneInvasionEvent( - const LaneInvasionEvent& x) -{ - m_header = x.m_header; - m_crossed_lane_markings = x.m_crossed_lane_markings; -} - -carla_msgs::msg::LaneInvasionEvent::LaneInvasionEvent( - LaneInvasionEvent&& x) noexcept -{ - m_header = std::move(x.m_header); - m_crossed_lane_markings = std::move(x.m_crossed_lane_markings); -} - -carla_msgs::msg::LaneInvasionEvent& carla_msgs::msg::LaneInvasionEvent::operator =( - const LaneInvasionEvent& x) -{ - m_header = x.m_header; - m_crossed_lane_markings = x.m_crossed_lane_markings; - - return *this; -} - -carla_msgs::msg::LaneInvasionEvent& carla_msgs::msg::LaneInvasionEvent::operator =( - LaneInvasionEvent&& x) noexcept -{ - m_header = std::move(x.m_header); - m_crossed_lane_markings = std::move(x.m_crossed_lane_markings); - - return *this; -} - -bool carla_msgs::msg::LaneInvasionEvent::operator ==( - const LaneInvasionEvent& x) const -{ - return (m_header == x.m_header && m_crossed_lane_markings == x.m_crossed_lane_markings); -} - -bool carla_msgs::msg::LaneInvasionEvent::operator !=( - const LaneInvasionEvent& x) const -{ - return !(*this == x); -} - -size_t carla_msgs::msg::LaneInvasionEvent::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return carla_msgs_msg_LaneInvasionEvent_max_cdr_typesize; -} - -size_t carla_msgs::msg::LaneInvasionEvent::getCdrSerializedSize( - const carla_msgs::msg::LaneInvasionEvent& 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); - - 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::LaneInvasionEvent::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_header; - scdr << m_crossed_lane_markings; -} - -void carla_msgs::msg::LaneInvasionEvent::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::LaneInvasionEvent::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::LaneInvasionEvent::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::LaneInvasionEvent::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::LaneInvasionEvent::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::LaneInvasionEvent::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::LaneInvasionEvent::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::LaneInvasionEvent::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::LaneInvasionEvent::crossed_lane_markings() -{ - return m_crossed_lane_markings; -} - - -size_t carla_msgs::msg::LaneInvasionEvent::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return carla_msgs_msg_LaneInvasionEvent_max_key_cdr_typesize; -} - -bool carla_msgs::msg::LaneInvasionEvent::isKeyDefined() -{ - return false; -} - -void carla_msgs::msg::LaneInvasionEvent::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/CarlaLineInvasion.h b/LibCarla/source/carla/ros2/types/CarlaLineInvasion.h deleted file mode 100644 index b1077107c40..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaLineInvasion.h +++ /dev/null @@ -1,242 +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 CarlaLineInvasion.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_ - -#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(CarlaLineInvasion_SOURCE) -#define CarlaLineInvasion_DllAPI __declspec( dllexport ) -#else -#define CarlaLineInvasion_DllAPI __declspec( dllimport ) -#endif // CarlaLineInvasion_SOURCE -#else -#define CarlaLineInvasion_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define CarlaLineInvasion_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 CARLALINEINVASION - */ - 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_CARLALINEINVASION_H_ diff --git a/LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.cpp deleted file mode 100644 index d23c113c4b2..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 CarlaLineInvasionPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "CarlaLineInvasionPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace carla_msgs { - namespace msg { - LaneInvasionEventPubSubType::LaneInvasionEventPubSubType() - { - setName("carla_msgs::msg::dds_::LaneInvasionEvent_"); - auto type_size = LaneInvasionEvent::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = LaneInvasionEvent::isKeyDefined(); - size_t keyLength = LaneInvasionEvent::getKeyMaxCdrSerializedSize() > 16 ? - LaneInvasionEvent::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - LaneInvasionEventPubSubType::~LaneInvasionEventPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool LaneInvasionEventPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - LaneInvasionEvent* 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 LaneInvasionEventPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - LaneInvasionEvent* 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; - } - - std::function LaneInvasionEventPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* LaneInvasionEventPubSubType::createData() - { - return reinterpret_cast(new LaneInvasionEvent()); - } - - void LaneInvasionEventPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool LaneInvasionEventPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - LaneInvasionEvent* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - LaneInvasionEvent::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || LaneInvasionEvent::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/CarlaLineInvasionPubSubTypes.h b/LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.h deleted file mode 100644 index a735ff75839..00000000000 --- a/LibCarla/source/carla/ros2/types/CarlaLineInvasionPubSubTypes.h +++ /dev/null @@ -1,105 +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 CarlaLineInvasionPubSubTypes.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_ - -#include -#include - -#include "CarlaLineInvasion.h" -#include "HeaderPubSubTypes.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. -#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 CARLALINEINVASION - */ - 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; - }; - } -} - -#endif // _FAST_DDS_GENERATED_CARLA_MSGS_MSG_CARLALINEINVASION_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Clock.cpp b/LibCarla/source/carla/ros2/types/Clock.cpp deleted file mode 100644 index 24bd064b6b2..00000000000 --- a/LibCarla/source/carla/ros2/types/Clock.cpp +++ /dev/null @@ -1,174 +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 Clock.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 "Clock.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define Time_max_cdr_typesize 0ULL; -#define rosgraph_msg_Clock_max_cdr_typesize 0ULL; -#define Time_max_key_cdr_typesize 0ULL; -#define rosgraph_msg_Clock_max_key_cdr_typesize 0ULL; - -rosgraph::msg::Clock::Clock() -{ -} - -rosgraph::msg::Clock::~Clock() -{ -} - -rosgraph::msg::Clock::Clock( - const rosgraph::msg::Clock& x) -{ - m_clock = x.m_clock; -} - -rosgraph::msg::Clock::Clock( - rosgraph::msg::Clock&& x) noexcept -{ - m_clock = x.m_clock; -} - -rosgraph::msg::Clock& rosgraph::msg::Clock::operator =( - const rosgraph::msg::Clock& x) -{ - m_clock = x.m_clock; - return *this; -} - -rosgraph::msg::Clock& rosgraph::msg::Clock::operator =( - rosgraph::msg::Clock&& x) noexcept -{ - m_clock = x.m_clock; - return *this; -} - -bool rosgraph::msg::Clock::operator ==( - const Clock& x) const -{ - return (m_clock == x.m_clock); -} - -bool rosgraph::msg::Clock::operator !=( - const Clock& x) const -{ - return !(*this == x); -} - -size_t rosgraph::msg::Clock::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return rosgraph_msg_Clock_max_cdr_typesize; -} - -size_t rosgraph::msg::Clock::getCdrSerializedSize( - const rosgraph::msg::Clock& data, - size_t current_alignment) -{ - (void)data; - size_t initial_alignment = current_alignment; - - - current_alignment += builtin_interfaces::msg::Time::getCdrSerializedSize(data.clock(), current_alignment); - - return current_alignment - initial_alignment; -} - -void rosgraph::msg::Clock::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_clock; -} - -void rosgraph::msg::Clock::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_clock; -} - -/*! - * @brief This function copies the value in member clock - * @param _clock New value to be copied in member clock - */ -void rosgraph::msg::Clock::clock( - const builtin_interfaces::msg::Time& _clock) -{ - m_clock = _clock; -} - -/*! - * @brief This function moves the value in member clock - * @param _clock New value to be moved in member clock - */ -void rosgraph::msg::Clock::clock( - builtin_interfaces::msg::Time&& _clock) -{ - m_clock = std::move(_clock); -} - -/*! - * @brief This function returns a constant reference to member clock - * @return Constant reference to member clock - */ -const builtin_interfaces::msg::Time& rosgraph::msg::Clock::clock() const -{ - return m_clock; -} - -/*! - * @brief This function returns a reference to member clock - * @return Reference to member clock - */ -builtin_interfaces::msg::Time& rosgraph::msg::Clock::clock() -{ - return m_clock; -} - -size_t rosgraph::msg::Clock::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return rosgraph_msg_Clock_max_key_cdr_typesize; -} - -bool rosgraph::msg::Clock::isKeyDefined() -{ - return false; -} - -void rosgraph::msg::Clock::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/Clock.h b/LibCarla/source/carla/ros2/types/Clock.h deleted file mode 100644 index 862b8193f49..00000000000 --- a/LibCarla/source/carla/ros2/types/Clock.h +++ /dev/null @@ -1,214 +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 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 "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/types/ClockPubSubTypes.cpp deleted file mode 100644 index 010968d776b..00000000000 --- a/LibCarla/source/carla/ros2/types/ClockPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 ClockPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "ClockPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace rosgraph { - namespace msg { - ClockPubSubType::ClockPubSubType() - { - setName("rosgraph_msgs::msg::dds_::Clock_"); - auto type_size = Clock::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Clock::isKeyDefined(); - size_t keyLength = Clock::getKeyMaxCdrSerializedSize() > 16 ? - Clock::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - ClockPubSubType::~ClockPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool ClockPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Clock* 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; - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - p_type->serialize(ser); - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload->length = static_cast(ser.getSerializedDataLength()); - return true; - } - - bool ClockPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - // Convert DATA to pointer of your type - Clock* 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::Exception& /*exception*/) - { - return false; - } - - return true; - } - - std::function ClockPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* ClockPubSubType::createData() - { - return reinterpret_cast(new Clock()); - } - - void ClockPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool ClockPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Clock* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Clock::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Clock::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 rosgraph diff --git a/LibCarla/source/carla/ros2/types/ClockPubSubTypes.h b/LibCarla/source/carla/ros2/types/ClockPubSubTypes.h deleted file mode 100644 index e3cb8ca3b1d..00000000000 --- a/LibCarla/source/carla/ros2/types/ClockPubSubTypes.h +++ /dev/null @@ -1,105 +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 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; - }; - } -} - -#endif // _FAST_DDS_GENERATED_ROSGRAPH_MSG_CLOCK_PUBSUBTYPES_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..d3853a809f8 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/CoordinateSystemTransform.h @@ -0,0 +1,52 @@ +// 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/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::Vector3D 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::Vector3D 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 carla::geom::Vector3D TransformLinearAxixVector3D(carla::geom::Vector3D const &carla_linear_values) { + carla::geom::Vector3D 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..d67c3aee2ce --- /dev/null +++ b/LibCarla/source/carla/ros2/types/EpisodeSettings.h @@ -0,0 +1,72 @@ +// 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/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/Float32.cpp b/LibCarla/source/carla/ros2/types/Float32.cpp deleted file mode 100644 index ea5c80d84ed..00000000000 --- a/LibCarla/source/carla/ros2/types/Float32.cpp +++ /dev/null @@ -1,160 +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 Float32.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 "Float32.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define std_msgs_msg_Float32_max_cdr_typesize 4ULL; -#define std_msgs_msg_Float32_max_key_cdr_typesize 0ULL; - -std_msgs::msg::Float32::Float32() -{ - m_data = 0.0; -} - -std_msgs::msg::Float32::~Float32() -{ -} - -std_msgs::msg::Float32::Float32( - const Float32& x) -{ - m_data = x.m_data; -} - -std_msgs::msg::Float32::Float32( - Float32&& x) noexcept -{ - m_data = x.m_data; -} - -std_msgs::msg::Float32& std_msgs::msg::Float32::operator =( - const Float32& x) -{ - m_data = x.m_data; - return *this; -} - -std_msgs::msg::Float32& std_msgs::msg::Float32::operator =( - Float32&& x) noexcept -{ - m_data = x.m_data; - return *this; -} - -bool std_msgs::msg::Float32::operator ==( - const Float32& x) const -{ - return (m_data == x.m_data); -} - -bool std_msgs::msg::Float32::operator !=( - const Float32& x) const -{ - return !(*this == x); -} - -size_t std_msgs::msg::Float32::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return std_msgs_msg_Float32_max_cdr_typesize; -} - -size_t std_msgs::msg::Float32::getCdrSerializedSize( - const std_msgs::msg::Float32& 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 std_msgs::msg::Float32::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_data; -} - -void std_msgs::msg::Float32::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_data; -} - -/*! - * @brief This function sets a value in member data - * @param _data New value for member data - */ -void std_msgs::msg::Float32::data( - float _data) -{ - m_data = _data; -} - -/*! - * @brief This function returns the value of member data - * @return Value of member data - */ -float std_msgs::msg::Float32::data() const -{ - return m_data; -} - -/*! - * @brief This function returns a reference to member data - * @return Reference to member data - */ -float& std_msgs::msg::Float32::data() -{ - return m_data; -} - -size_t std_msgs::msg::Float32::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return std_msgs_msg_Float32_max_key_cdr_typesize; -} - -bool std_msgs::msg::Float32::isKeyDefined() -{ - return false; -} - -void std_msgs::msg::Float32::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/Float32.h b/LibCarla/source/carla/ros2/types/Float32.h deleted file mode 100644 index e857e2c10a3..00000000000 --- a/LibCarla/source/carla/ros2/types/Float32.h +++ /dev/null @@ -1,204 +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 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/types/Float32PubSubTypes.cpp deleted file mode 100644 index 844ad6011d2..00000000000 --- a/LibCarla/source/carla/ros2/types/Float32PubSubTypes.cpp +++ /dev/null @@ -1,172 +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.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "Float32PubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace std_msgs { - namespace msg { - Float32PubSubType::Float32PubSubType() - { - setName("std_msgs::msg::dds_::Float32_"); - auto type_size = Float32::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Float32::isKeyDefined(); - size_t keyLength = Float32::getKeyMaxCdrSerializedSize() > 16 ? - Float32::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - Float32PubSubType::~Float32PubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool Float32PubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Float32* 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 Float32PubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - Float32* 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; - } - - std::function Float32PubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* Float32PubSubType::createData() - { - return reinterpret_cast(new Float32()); - } - - void Float32PubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool Float32PubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Float32* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Float32::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Float32::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 std_msgs diff --git a/LibCarla/source/carla/ros2/types/Float32PubSubTypes.h b/LibCarla/source/carla/ros2/types/Float32PubSubTypes.h deleted file mode 100644 index baefe1fd241..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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*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/Header.cpp b/LibCarla/source/carla/ros2/types/Header.cpp deleted file mode 100644 index 04d098fe866..00000000000 --- a/LibCarla/source/carla/ros2/types/Header.cpp +++ /dev/null @@ -1,219 +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 Header.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 "Header.h" -#include - -#include -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_frame_id =""; -} - -std_msgs::msg::Header::~Header() -{ -} - -std_msgs::msg::Header::Header( - const Header& x) -{ - m_stamp = x.m_stamp; - m_frame_id = x.m_frame_id; -} - -std_msgs::msg::Header::Header( - Header&& x) noexcept -{ - m_stamp = std::move(x.m_stamp); - m_frame_id = std::move(x.m_frame_id); -} - -std_msgs::msg::Header& std_msgs::msg::Header::operator =( - const Header& x) -{ - m_stamp = x.m_stamp; - m_frame_id = x.m_frame_id; - - return *this; -} - -std_msgs::msg::Header& std_msgs::msg::Header::operator =( - Header&& x) noexcept -{ - m_stamp = std::move(x.m_stamp); - m_frame_id = std::move(x.m_frame_id); - - return *this; -} - -bool std_msgs::msg::Header::operator ==( - const Header& x) const -{ - return (m_stamp == x.m_stamp && m_frame_id == x.m_frame_id); -} - -bool std_msgs::msg::Header::operator !=( - const Header& x) const -{ - return !(*this == x); -} - -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 std_msgs::msg::Header::getCdrSerializedSize( - const std_msgs::msg::Header& data, - size_t current_alignment) -{ - 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(); -} - -void std_msgs::msg::Header::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_stamp; - dcdr >> m_frame_id; -} - -/*! - * @brief This function copies the value in member stamp - * @param _stamp New value to be copied in member stamp - */ -void std_msgs::msg::Header::stamp( - const builtin_interfaces::msg::Time& _stamp) -{ - m_stamp = _stamp; -} - -/*! - * @brief This function moves the value in member stamp - * @param _stamp New value to be moved in member stamp - */ -void std_msgs::msg::Header::stamp( - builtin_interfaces::msg::Time&& _stamp) -{ - m_stamp = std::move(_stamp); -} - -/*! - * @brief This function returns a constant reference to member stamp - * @return Constant reference to member stamp - */ -const builtin_interfaces::msg::Time& std_msgs::msg::Header::stamp() const -{ - return m_stamp; -} - -/*! - * @brief This function returns a reference to member stamp - * @return Reference to member stamp - */ -builtin_interfaces::msg::Time& std_msgs::msg::Header::stamp() -{ - return m_stamp; -} -/*! - * @brief This function copies the value in member frame_id - * @param _frame_id New value to be copied in member frame_id - */ -void std_msgs::msg::Header::frame_id( - const std::string& _frame_id) -{ - m_frame_id = _frame_id; -} - -/*! - * @brief This function moves the value in member frame_id - * @param _frame_id New value to be moved in member frame_id - */ -void std_msgs::msg::Header::frame_id( - std::string&& _frame_id) -{ - m_frame_id = std::move(_frame_id); -} - -/*! - * @brief This function returns a constant reference to member frame_id - * @return Constant reference to member frame_id - */ -const std::string& std_msgs::msg::Header::frame_id() const -{ - return m_frame_id; -} - -/*! - * @brief This function returns a reference to member frame_id - * @return Reference to member frame_id - */ -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; -} - -bool std_msgs::msg::Header::isKeyDefined() -{ - return false; -} - -void std_msgs::msg::Header::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/Header.h b/LibCarla/source/carla/ros2/types/Header.h deleted file mode 100644 index 81a050caca3..00000000000 --- a/LibCarla/source/carla/ros2/types/Header.h +++ /dev/null @@ -1,240 +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 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 "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(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) noexcept; - - /*! - * @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) noexcept; - - /*! - * @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_ diff --git a/LibCarla/source/carla/ros2/types/HeaderPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/HeaderPubSubTypes.cpp deleted file mode 100644 index e61f4ee873c..00000000000 --- a/LibCarla/source/carla/ros2/types/HeaderPubSubTypes.cpp +++ /dev/null @@ -1,154 +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 HeaderPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "HeaderPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace std_msgs { - namespace msg { - HeaderPubSubType::HeaderPubSubType() - { - setName("std_msgs::msg::dds_::Header_"); - auto type_size = Header::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Header::isKeyDefined(); - size_t keyLength = Header::getKeyMaxCdrSerializedSize() > 16 ? - Header::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - HeaderPubSubType::~HeaderPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool HeaderPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Header* 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; - } - - bool HeaderPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - //Convert DATA to pointer of your type - Header* 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; - } - - std::function HeaderPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* HeaderPubSubType::createData() - { - return reinterpret_cast(new Header()); - } - - void HeaderPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool HeaderPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Header* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Header::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Header::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 std_msgs diff --git a/LibCarla/source/carla/ros2/types/HeaderPubSubTypes.h b/LibCarla/source/carla/ros2/types/HeaderPubSubTypes.h deleted file mode 100644 index ddc9ca2b87c..00000000000 --- a/LibCarla/source/carla/ros2/types/HeaderPubSubTypes.h +++ /dev/null @@ -1,106 +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 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 "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() 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; - }; - } -} - -#endif // _FAST_DDS_GENERATED_STD_MSGS_MSG_HEADER_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/Image.h b/LibCarla/source/carla/ros2/types/Image.h deleted file mode 100644 index 3f8114c04d7..00000000000 --- a/LibCarla/source/carla/ros2/types/Image.h +++ /dev/null @@ -1,347 +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.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_ - -#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(Image_SOURCE) -#define Image_DllAPI __declspec( dllexport ) -#else -#define Image_DllAPI __declspec( dllimport ) -#endif // Image_SOURCE -#else -#define Image_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define Image_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace sensor_msgs { - namespace msg { - /*! - * @brief This class represents the structure Image defined by the user in the IDL file. - * @ingroup IMAGE - */ - class Image - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Image(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Image(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object sensor_msgs::msg::Image that will be copied. - */ - eProsima_user_DllExport Image( - const Image& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object sensor_msgs::msg::Image that will be copied. - */ - eProsima_user_DllExport Image( - Image&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object sensor_msgs::msg::Image that will be copied. - */ - eProsima_user_DllExport Image& operator =( - const Image& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object sensor_msgs::msg::Image that will be copied. - */ - eProsima_user_DllExport Image& operator =( - Image&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::Image object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Image& x) const; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::Image object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Image& 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 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 sensor_msgs::msg::Image& 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; - std::vector m_data; - }; - } // namespace msg -} // namespace sensor_msgs - -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_IMAGE_H_ diff --git a/LibCarla/source/carla/ros2/types/ImagePubSubTypes.cpp b/LibCarla/source/carla/ros2/types/ImagePubSubTypes.cpp deleted file mode 100644 index cadfdf9908b..00000000000 --- a/LibCarla/source/carla/ros2/types/ImagePubSubTypes.cpp +++ /dev/null @@ -1,154 +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 ImagePubSubTypes.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 { - ImagePubSubType::ImagePubSubType() - { - setName("sensor_msgs::msg::dds_::Image_"); - auto type_size = Image::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_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - ImagePubSubType::~ImagePubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool ImagePubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Image* 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; - } - - bool ImagePubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - //Convert DATA to pointer of your type - Image* 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; - } - - std::function ImagePubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* ImagePubSubType::createData() - { - return reinterpret_cast(new Image()); - } - - void ImagePubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool ImagePubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Image* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Image::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) - { - 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/types/ImagePubSubTypes.h b/LibCarla/source/carla/ros2/types/ImagePubSubTypes.h deleted file mode 100644 index 499844880ac..00000000000 --- a/LibCarla/source/carla/ros2/types/ImagePubSubTypes.h +++ /dev/null @@ -1,105 +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 ImagePubSubTypes.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 - */ - class ImagePubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef Image type; - - eProsima_user_DllExport ImagePubSubType(); - - eProsima_user_DllExport virtual ~ImagePubSubType() 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; - }; - } -} - -#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/types/Imu.cpp deleted file mode 100644 index ece90e125d4..00000000000 --- a/LibCarla/source/carla/ros2/types/Imu.cpp +++ /dev/null @@ -1,465 +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.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 "Imu.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define geometry_msgs_msg_Vector3_max_cdr_typesize 24ULL; -#define std_msgs_msg_Time_max_cdr_typesize 8ULL; - -#define geometry_msgs_msg_Quaternion_max_cdr_typesize 32ULL; -#define std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define sensor_msgs_msg_Imu_max_cdr_typesize 568ULL; -#define geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Time_max_key_cdr_typesize 0ULL; - -#define geometry_msgs_msg_Quaternion_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; -#define sensor_msgs_msg_Imu_max_key_cdr_typesize 0ULL; - -sensor_msgs::msg::Imu::Imu() -{ - // std_msgs::msg::Header m_header - - // geometry_msgs::msg::Quaternion m_orientation - - // sensor_msgs::msg::sensor_msgs__Imu__double_array_9 m_orientation_covariance - memset(&m_orientation_covariance, 0, (9) * 8); - // geometry_msgs::msg::Vector3 m_angular_velocity - - // sensor_msgs::msg::sensor_msgs__Imu__double_array_9 m_angular_velocity_covariance - memset(&m_angular_velocity_covariance, 0, (9) * 8); - // geometry_msgs::msg::Vector3 m_linear_acceleration - - // sensor_msgs::msg::sensor_msgs__Imu__double_array_9 m_linear_acceleration_covariance - memset(&m_linear_acceleration_covariance, 0, (9) * 8); -} - -sensor_msgs::msg::Imu::~Imu() -{ -} - -sensor_msgs::msg::Imu::Imu( - const Imu& x) -{ - m_header = x.m_header; - m_orientation = x.m_orientation; - m_orientation_covariance = x.m_orientation_covariance; - m_angular_velocity = x.m_angular_velocity; - m_angular_velocity_covariance = x.m_angular_velocity_covariance; - m_linear_acceleration = x.m_linear_acceleration; - m_linear_acceleration_covariance = x.m_linear_acceleration_covariance; -} - -sensor_msgs::msg::Imu::Imu( - Imu&& x) noexcept -{ - m_header = std::move(x.m_header); - m_orientation = std::move(x.m_orientation); - m_orientation_covariance = std::move(x.m_orientation_covariance); - m_angular_velocity = std::move(x.m_angular_velocity); - m_angular_velocity_covariance = std::move(x.m_angular_velocity_covariance); - m_linear_acceleration = std::move(x.m_linear_acceleration); - m_linear_acceleration_covariance = std::move(x.m_linear_acceleration_covariance); -} - -sensor_msgs::msg::Imu& sensor_msgs::msg::Imu::operator =( - const Imu& x) -{ - m_header = x.m_header; - m_orientation = x.m_orientation; - m_orientation_covariance = x.m_orientation_covariance; - m_angular_velocity = x.m_angular_velocity; - m_angular_velocity_covariance = x.m_angular_velocity_covariance; - m_linear_acceleration = x.m_linear_acceleration; - m_linear_acceleration_covariance = x.m_linear_acceleration_covariance; - - return *this; -} - -sensor_msgs::msg::Imu& sensor_msgs::msg::Imu::operator =( - Imu&& x) noexcept -{ - m_header = std::move(x.m_header); - m_orientation = std::move(x.m_orientation); - m_orientation_covariance = std::move(x.m_orientation_covariance); - m_angular_velocity = std::move(x.m_angular_velocity); - m_angular_velocity_covariance = std::move(x.m_angular_velocity_covariance); - m_linear_acceleration = std::move(x.m_linear_acceleration); - m_linear_acceleration_covariance = std::move(x.m_linear_acceleration_covariance); - - return *this; -} - -bool sensor_msgs::msg::Imu::operator ==( - const Imu& x) const -{ - return (m_header == x.m_header && m_orientation == x.m_orientation && m_orientation_covariance == x.m_orientation_covariance && m_angular_velocity == x.m_angular_velocity && m_angular_velocity_covariance == x.m_angular_velocity_covariance && m_linear_acceleration == x.m_linear_acceleration && m_linear_acceleration_covariance == x.m_linear_acceleration_covariance); -} - -bool sensor_msgs::msg::Imu::operator !=( - const Imu& x) const -{ - return !(*this == x); -} - -size_t sensor_msgs::msg::Imu::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_Imu_max_cdr_typesize; -} - -size_t sensor_msgs::msg::Imu::getCdrSerializedSize( - const sensor_msgs::msg::Imu& data, - size_t current_alignment) -{ - size_t initial_alignment = current_alignment; - current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); - current_alignment += geometry_msgs::msg::Quaternion::getCdrSerializedSize(data.orientation(), current_alignment); - current_alignment += ((9) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); - current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.angular_velocity(), current_alignment); - current_alignment += ((9) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); - current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.linear_acceleration(), current_alignment); - current_alignment += ((9) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); - - return current_alignment - initial_alignment; -} - -void sensor_msgs::msg::Imu::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_header; - scdr << m_orientation; - scdr << m_orientation_covariance; - scdr << m_angular_velocity; - scdr << m_angular_velocity_covariance; - scdr << m_linear_acceleration; - scdr << m_linear_acceleration_covariance; -} - -void sensor_msgs::msg::Imu::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_header; - dcdr >> m_orientation; - dcdr >> m_orientation_covariance; - dcdr >> m_angular_velocity; - dcdr >> m_angular_velocity_covariance; - dcdr >> m_linear_acceleration; - dcdr >> m_linear_acceleration_covariance; -} - -/*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ -void sensor_msgs::msg::Imu::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::Imu::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::Imu::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::Imu::header() -{ - return m_header; -} - -/*! - * @brief This function copies the value in member orientation - * @param _orientation New value to be copied in member orientation - */ -void sensor_msgs::msg::Imu::orientation( - const geometry_msgs::msg::Quaternion& _orientation) -{ - m_orientation = _orientation; -} - -/*! - * @brief This function moves the value in member orientation - * @param _orientation New value to be moved in member orientation - */ -void sensor_msgs::msg::Imu::orientation( - geometry_msgs::msg::Quaternion&& _orientation) -{ - m_orientation = std::move(_orientation); -} - -/*! - * @brief This function returns a constant reference to member orientation - * @return Constant reference to member orientation - */ -const geometry_msgs::msg::Quaternion& sensor_msgs::msg::Imu::orientation() const -{ - return m_orientation; -} - -/*! - * @brief This function returns a reference to member orientation - * @return Reference to member orientation - */ -geometry_msgs::msg::Quaternion& sensor_msgs::msg::Imu::orientation() -{ - return m_orientation; -} - -/*! - * @brief This function copies the value in member orientation_covariance - * @param _orientation_covariance New value to be copied in member orientation_covariance - */ -void sensor_msgs::msg::Imu::orientation_covariance( - const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& _orientation_covariance) -{ - m_orientation_covariance = _orientation_covariance; -} - -/*! - * @brief This function moves the value in member orientation_covariance - * @param _orientation_covariance New value to be moved in member orientation_covariance - */ -void sensor_msgs::msg::Imu::orientation_covariance( - sensor_msgs::msg::sensor_msgs__Imu__double_array_9&& _orientation_covariance) -{ - m_orientation_covariance = std::move(_orientation_covariance); -} - -/*! - * @brief This function returns a constant reference to member orientation_covariance - * @return Constant reference to member orientation_covariance - */ -const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& sensor_msgs::msg::Imu::orientation_covariance() const -{ - return m_orientation_covariance; -} - -/*! - * @brief This function returns a reference to member orientation_covariance - * @return Reference to member orientation_covariance - */ -sensor_msgs::msg::sensor_msgs__Imu__double_array_9& sensor_msgs::msg::Imu::orientation_covariance() -{ - return m_orientation_covariance; -} - -/*! - * @brief This function copies the value in member angular_velocity - * @param _angular_velocity New value to be copied in member angular_velocity - */ -void sensor_msgs::msg::Imu::angular_velocity( - const geometry_msgs::msg::Vector3& _angular_velocity) -{ - m_angular_velocity = _angular_velocity; -} - -/*! - * @brief This function moves the value in member angular_velocity - * @param _angular_velocity New value to be moved in member angular_velocity - */ -void sensor_msgs::msg::Imu::angular_velocity( - geometry_msgs::msg::Vector3&& _angular_velocity) -{ - m_angular_velocity = std::move(_angular_velocity); -} - -/*! - * @brief This function returns a constant reference to member angular_velocity - * @return Constant reference to member angular_velocity - */ -const geometry_msgs::msg::Vector3& sensor_msgs::msg::Imu::angular_velocity() const -{ - return m_angular_velocity; -} - -/*! - * @brief This function returns a reference to member angular_velocity - * @return Reference to member angular_velocity - */ -geometry_msgs::msg::Vector3& sensor_msgs::msg::Imu::angular_velocity() -{ - return m_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 - */ -void sensor_msgs::msg::Imu::angular_velocity_covariance( - const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& _angular_velocity_covariance) -{ - m_angular_velocity_covariance = _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 - */ -void sensor_msgs::msg::Imu::angular_velocity_covariance( - sensor_msgs::msg::sensor_msgs__Imu__double_array_9&& _angular_velocity_covariance) -{ - m_angular_velocity_covariance = std::move(_angular_velocity_covariance); -} - -/*! - * @brief This function returns a constant reference to member angular_velocity_covariance - * @return Constant reference to member angular_velocity_covariance - */ -const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& sensor_msgs::msg::Imu::angular_velocity_covariance() const -{ - return m_angular_velocity_covariance; -} - -/*! - * @brief This function returns a reference to member angular_velocity_covariance - * @return Reference to member angular_velocity_covariance - */ -sensor_msgs::msg::sensor_msgs__Imu__double_array_9& sensor_msgs::msg::Imu::angular_velocity_covariance() -{ - return m_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 - */ -void sensor_msgs::msg::Imu::linear_acceleration( - const geometry_msgs::msg::Vector3& _linear_acceleration) -{ - m_linear_acceleration = _linear_acceleration; -} - -/*! - * @brief This function moves the value in member linear_acceleration - * @param _linear_acceleration New value to be moved in member linear_acceleration - */ -void sensor_msgs::msg::Imu::linear_acceleration( - geometry_msgs::msg::Vector3&& _linear_acceleration) -{ - m_linear_acceleration = std::move(_linear_acceleration); -} - -/*! - * @brief This function returns a constant reference to member linear_acceleration - * @return Constant reference to member linear_acceleration - */ -const geometry_msgs::msg::Vector3& sensor_msgs::msg::Imu::linear_acceleration() const -{ - return m_linear_acceleration; -} - -/*! - * @brief This function returns a reference to member linear_acceleration - * @return Reference to member linear_acceleration - */ -geometry_msgs::msg::Vector3& sensor_msgs::msg::Imu::linear_acceleration() -{ - return m_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 - */ -void sensor_msgs::msg::Imu::linear_acceleration_covariance( - const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& _linear_acceleration_covariance) -{ - m_linear_acceleration_covariance = _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 - */ -void sensor_msgs::msg::Imu::linear_acceleration_covariance( - sensor_msgs::msg::sensor_msgs__Imu__double_array_9&& _linear_acceleration_covariance) -{ - m_linear_acceleration_covariance = std::move(_linear_acceleration_covariance); -} - -/*! - * @brief This function returns a constant reference to member linear_acceleration_covariance - * @return Constant reference to member linear_acceleration_covariance - */ -const sensor_msgs::msg::sensor_msgs__Imu__double_array_9& sensor_msgs::msg::Imu::linear_acceleration_covariance() const -{ - return m_linear_acceleration_covariance; -} - -/*! - * @brief This function returns a reference to member linear_acceleration_covariance - * @return Reference to member linear_acceleration_covariance - */ -sensor_msgs::msg::sensor_msgs__Imu__double_array_9& sensor_msgs::msg::Imu::linear_acceleration_covariance() -{ - return m_linear_acceleration_covariance; -} - -size_t sensor_msgs::msg::Imu::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_Imu_max_key_cdr_typesize; -} - -bool sensor_msgs::msg::Imu::isKeyDefined() -{ - return false; -} - -void sensor_msgs::msg::Imu::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/ImuPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/ImuPubSubTypes.cpp deleted file mode 100644 index 865d455d0c8..00000000000 --- a/LibCarla/source/carla/ros2/types/ImuPubSubTypes.cpp +++ /dev/null @@ -1,173 +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 ImuPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "ImuPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace sensor_msgs { - namespace msg { - - ImuPubSubType::ImuPubSubType() - { - setName("sensor_msgs::msg::dds_::Imu_"); - auto type_size = Imu::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Imu::isKeyDefined(); - size_t keyLength = Imu::getKeyMaxCdrSerializedSize() > 16 ? - Imu::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - ImuPubSubType::~ImuPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool ImuPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Imu* 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 ImuPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - Imu* 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; - } - - std::function ImuPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* ImuPubSubType::createData() - { - return reinterpret_cast(new Imu()); - } - - void ImuPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool ImuPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Imu* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Imu::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Imu::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/types/ImuPubSubTypes.h b/LibCarla/source/carla/ros2/types/ImuPubSubTypes.h deleted file mode 100644 index 1dcca34f3e1..00000000000 --- a/LibCarla/source/carla/ros2/types/ImuPubSubTypes.h +++ /dev/null @@ -1,111 +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 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 "Vector3PubSubTypes.h" -#include "QuaternionPubSubTypes.h" -#include "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; - }; - } -} - -#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/types/NavSatFix.cpp deleted file mode 100644 index db462c96231..00000000000 --- a/LibCarla/source/carla/ros2/types/NavSatFix.cpp +++ /dev/null @@ -1,421 +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.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 "NavSatFix.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define std_msgs_msg_Time_max_cdr_typesize 8ULL; -#define sensor_msgs_msg_NavSatStatus_max_cdr_typesize 4ULL; -#define std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define sensor_msgs_msg_NavSatFix_max_cdr_typesize 369ULL; - -#define std_msgs_msg_Time_max_key_cdr_typesize 0ULL; -#define sensor_msgs_msg_NavSatStatus_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; -#define sensor_msgs_msg_NavSatFix_max_key_cdr_typesize 0ULL; - -sensor_msgs::msg::NavSatFix::NavSatFix() -{ - // std_msgs::msg::Header m_header - - // sensor_msgs::msg::NavSatStatus m_status - - // double m_latitude - m_latitude = 0.0; - // double m_longitude - m_longitude = 0.0; - // double m_altitude - m_altitude = 0.0; - // sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9 m_position_covariance - memset(&m_position_covariance, 0, (9) * 8); - // octet m_position_covariance_type - m_position_covariance_type = 0; -} - -sensor_msgs::msg::NavSatFix::~NavSatFix() -{ -} - -sensor_msgs::msg::NavSatFix::NavSatFix( - const NavSatFix& x) -{ - m_header = x.m_header; - m_status = x.m_status; - m_latitude = x.m_latitude; - m_longitude = x.m_longitude; - m_altitude = x.m_altitude; - m_position_covariance = x.m_position_covariance; - m_position_covariance_type = x.m_position_covariance_type; -} - -sensor_msgs::msg::NavSatFix::NavSatFix( - NavSatFix&& x) noexcept -{ - m_header = std::move(x.m_header); - m_status = std::move(x.m_status); - m_latitude = x.m_latitude; - m_longitude = x.m_longitude; - m_altitude = x.m_altitude; - m_position_covariance = std::move(x.m_position_covariance); - m_position_covariance_type = x.m_position_covariance_type; -} - -sensor_msgs::msg::NavSatFix& sensor_msgs::msg::NavSatFix::operator =( - const NavSatFix& x) -{ - m_header = x.m_header; - m_status = x.m_status; - m_latitude = x.m_latitude; - m_longitude = x.m_longitude; - m_altitude = x.m_altitude; - m_position_covariance = x.m_position_covariance; - m_position_covariance_type = x.m_position_covariance_type; - - return *this; -} - -sensor_msgs::msg::NavSatFix& sensor_msgs::msg::NavSatFix::operator =( - NavSatFix&& x) noexcept -{ - m_header = std::move(x.m_header); - m_status = std::move(x.m_status); - m_latitude = x.m_latitude; - m_longitude = x.m_longitude; - m_altitude = x.m_altitude; - m_position_covariance = std::move(x.m_position_covariance); - m_position_covariance_type = x.m_position_covariance_type; - - return *this; -} - -bool sensor_msgs::msg::NavSatFix::operator ==( - const NavSatFix& x) const -{ - return (m_header == x.m_header && m_status == x.m_status && m_latitude == x.m_latitude && m_longitude == x.m_longitude && m_altitude == x.m_altitude && m_position_covariance == x.m_position_covariance && m_position_covariance_type == x.m_position_covariance_type); -} - -bool sensor_msgs::msg::NavSatFix::operator !=( - const NavSatFix& x) const -{ - return !(*this == x); -} - -size_t sensor_msgs::msg::NavSatFix::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_NavSatFix_max_cdr_typesize; -} - -size_t sensor_msgs::msg::NavSatFix::getCdrSerializedSize( - const sensor_msgs::msg::NavSatFix& data, - size_t current_alignment) -{ - size_t initial_alignment = current_alignment; - current_alignment += std_msgs::msg::Header::getCdrSerializedSize(data.header(), current_alignment); - current_alignment += sensor_msgs::msg::NavSatStatus::getCdrSerializedSize(data.status(), 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 += ((9) * 8) + eprosima::fastcdr::Cdr::alignment(current_alignment, 8); - current_alignment += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); - - return current_alignment - initial_alignment; -} - -void sensor_msgs::msg::NavSatFix::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_header; - scdr << m_status; - scdr << m_latitude; - scdr << m_longitude; - scdr << m_altitude; - scdr << m_position_covariance; - scdr << m_position_covariance_type; -} - -void sensor_msgs::msg::NavSatFix::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_header; - dcdr >> m_status; - dcdr >> m_latitude; - dcdr >> m_longitude; - dcdr >> m_altitude; - dcdr >> m_position_covariance; - dcdr >> m_position_covariance_type; -} - -/*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ -void sensor_msgs::msg::NavSatFix::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::NavSatFix::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::NavSatFix::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::NavSatFix::header() -{ - return m_header; -} - -/*! - * @brief This function copies the value in member status - * @param _status New value to be copied in member status - */ -void sensor_msgs::msg::NavSatFix::status( - const sensor_msgs::msg::NavSatStatus& _status) -{ - m_status = _status; -} - -/*! - * @brief This function moves the value in member status - * @param _status New value to be moved in member status - */ -void sensor_msgs::msg::NavSatFix::status( - sensor_msgs::msg::NavSatStatus&& _status) -{ - m_status = std::move(_status); -} - -/*! - * @brief This function returns a constant reference to member status - * @return Constant reference to member status - */ -const sensor_msgs::msg::NavSatStatus& sensor_msgs::msg::NavSatFix::status() const -{ - return m_status; -} - -/*! - * @brief This function returns a reference to member status - * @return Reference to member status - */ -sensor_msgs::msg::NavSatStatus& sensor_msgs::msg::NavSatFix::status() -{ - return m_status; -} - -/*! - * @brief This function sets a value in member latitude - * @param _latitude New value for member latitude - */ -void sensor_msgs::msg::NavSatFix::latitude( - double _latitude) -{ - m_latitude = _latitude; -} - -/*! - * @brief This function returns the value of member latitude - * @return Value of member latitude - */ -double sensor_msgs::msg::NavSatFix::latitude() const -{ - return m_latitude; -} - -/*! - * @brief This function returns a reference to member latitude - * @return Reference to member latitude - */ -double& sensor_msgs::msg::NavSatFix::latitude() -{ - return m_latitude; -} - -/*! - * @brief This function sets a value in member longitude - * @param _longitude New value for member longitude - */ -void sensor_msgs::msg::NavSatFix::longitude( - double _longitude) -{ - m_longitude = _longitude; -} - -/*! - * @brief This function returns the value of member longitude - * @return Value of member longitude - */ -double sensor_msgs::msg::NavSatFix::longitude() const -{ - return m_longitude; -} - -/*! - * @brief This function returns a reference to member longitude - * @return Reference to member longitude - */ -double& sensor_msgs::msg::NavSatFix::longitude() -{ - return m_longitude; -} - -/*! - * @brief This function sets a value in member altitude - * @param _altitude New value for member altitude - */ -void sensor_msgs::msg::NavSatFix::altitude( - double _altitude) -{ - m_altitude = _altitude; -} - -/*! - * @brief This function returns the value of member altitude - * @return Value of member altitude - */ -double sensor_msgs::msg::NavSatFix::altitude() const -{ - return m_altitude; -} - -/*! - * @brief This function returns a reference to member altitude - * @return Reference to member altitude - */ -double& sensor_msgs::msg::NavSatFix::altitude() -{ - return m_altitude; -} - -/*! - * @brief This function copies the value in member position_covariance - * @param _position_covariance New value to be copied in member position_covariance - */ -void sensor_msgs::msg::NavSatFix::position_covariance( - const sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9& _position_covariance) -{ - m_position_covariance = _position_covariance; -} - -/*! - * @brief This function moves the value in member position_covariance - * @param _position_covariance New value to be moved in member position_covariance - */ -void sensor_msgs::msg::NavSatFix::position_covariance( - sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9&& _position_covariance) -{ - m_position_covariance = std::move(_position_covariance); -} - -/*! - * @brief This function returns a constant reference to member position_covariance - * @return Constant reference to member position_covariance - */ -const sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9& sensor_msgs::msg::NavSatFix::position_covariance() const -{ - return m_position_covariance; -} - -/*! - * @brief This function returns a reference to member position_covariance - * @return Reference to member position_covariance - */ -sensor_msgs::msg::sensor_msgs__NavSatFix__double_array_9& sensor_msgs::msg::NavSatFix::position_covariance() -{ - return m_position_covariance; -} -/*! - * @brief This function sets a value in member position_covariance_type - * @param _position_covariance_type New value for member position_covariance_type - */ -void sensor_msgs::msg::NavSatFix::position_covariance_type( - uint8_t _position_covariance_type) -{ - m_position_covariance_type = _position_covariance_type; -} - -/*! - * @brief This function returns the value of member position_covariance_type - * @return Value of member position_covariance_type - */ -uint8_t sensor_msgs::msg::NavSatFix::position_covariance_type() const -{ - return m_position_covariance_type; -} - -/*! - * @brief This function returns a reference to member position_covariance_type - * @return Reference to member position_covariance_type - */ -uint8_t& sensor_msgs::msg::NavSatFix::position_covariance_type() -{ - return m_position_covariance_type; -} - -size_t sensor_msgs::msg::NavSatFix::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_NavSatFix_max_key_cdr_typesize; -} - -bool sensor_msgs::msg::NavSatFix::isKeyDefined() -{ - return false; -} - -void sensor_msgs::msg::NavSatFix::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} 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/NavSatFixPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/NavSatFixPubSubTypes.cpp deleted file mode 100644 index a975d95adfa..00000000000 --- a/LibCarla/source/carla/ros2/types/NavSatFixPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 NavSatFixPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "NavSatFixPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace sensor_msgs { - namespace msg { - NavSatFixPubSubType::NavSatFixPubSubType() - { - setName("sensor_msgs::msg::dds_::NavSatFix_"); - auto type_size = NavSatFix::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = NavSatFix::isKeyDefined(); - size_t keyLength = NavSatFix::getKeyMaxCdrSerializedSize() > 16 ? - NavSatFix::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - NavSatFixPubSubType::~NavSatFixPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool NavSatFixPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - NavSatFix* 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 NavSatFixPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - NavSatFix* 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; - } - - std::function NavSatFixPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* NavSatFixPubSubType::createData() - { - return reinterpret_cast(new NavSatFix()); - } - - void NavSatFixPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool NavSatFixPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - NavSatFix* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - NavSatFix::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || NavSatFix::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/types/NavSatFixPubSubTypes.h b/LibCarla/source/carla/ros2/types/NavSatFixPubSubTypes.h deleted file mode 100644 index d6bf7437198..00000000000 --- a/LibCarla/source/carla/ros2/types/NavSatFixPubSubTypes.h +++ /dev/null @@ -1,110 +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 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 "HeaderPubSubTypes.h" -#include "NavSatStatusPubSubTypes.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; - }; - } -} - -#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/types/NavSatStatus.cpp deleted file mode 100644 index 5e2f6029e8c..00000000000 --- a/LibCarla/source/carla/ros2/types/NavSatStatus.cpp +++ /dev/null @@ -1,201 +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 NavSatStatus.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 "NavSatStatus.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define sensor_msgs_msg_NavSatStatus_max_cdr_typesize 4ULL; -#define sensor_msgs_msg_NavSatStatus_max_key_cdr_typesize 0ULL; - -sensor_msgs::msg::NavSatStatus::NavSatStatus() -{ - // octet m_status - m_status = 0; - // unsigned short m_service - m_service = 0; -} - -sensor_msgs::msg::NavSatStatus::~NavSatStatus() -{ -} - -sensor_msgs::msg::NavSatStatus::NavSatStatus( - const NavSatStatus& x) -{ - m_status = x.m_status; - m_service = x.m_service; -} - -sensor_msgs::msg::NavSatStatus::NavSatStatus( - NavSatStatus&& x) noexcept -{ - m_status = x.m_status; - m_service = x.m_service; -} - -sensor_msgs::msg::NavSatStatus& sensor_msgs::msg::NavSatStatus::operator =( - const NavSatStatus& x) -{ - m_status = x.m_status; - m_service = x.m_service; - - return *this; -} - -sensor_msgs::msg::NavSatStatus& sensor_msgs::msg::NavSatStatus::operator =( - NavSatStatus&& x) noexcept -{ - m_status = x.m_status; - m_service = x.m_service; - - return *this; -} - -bool sensor_msgs::msg::NavSatStatus::operator ==( - const NavSatStatus& x) const -{ - return (m_status == x.m_status && m_service == x.m_service); -} - -bool sensor_msgs::msg::NavSatStatus::operator !=( - const NavSatStatus& x) const -{ - return !(*this == x); -} - -size_t sensor_msgs::msg::NavSatStatus::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_NavSatStatus_max_cdr_typesize; -} - -size_t sensor_msgs::msg::NavSatStatus::getCdrSerializedSize( - const sensor_msgs::msg::NavSatStatus& 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 += 2 + eprosima::fastcdr::Cdr::alignment(current_alignment, 2); - - return current_alignment - initial_alignment; -} - -void sensor_msgs::msg::NavSatStatus::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_status; - scdr << m_service; -} - -void sensor_msgs::msg::NavSatStatus::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_status; - dcdr >> m_service; -} - -/*! - * @brief This function sets a value in member status - * @param _status New value for member status - */ -void sensor_msgs::msg::NavSatStatus::status( - uint8_t _status) -{ - m_status = _status; -} - -/*! - * @brief This function returns the value of member status - * @return Value of member status - */ -uint8_t sensor_msgs::msg::NavSatStatus::status() const -{ - return m_status; -} - -/*! - * @brief This function returns a reference to member status - * @return Reference to member status - */ -uint8_t& sensor_msgs::msg::NavSatStatus::status() -{ - return m_status; -} - -/*! - * @brief This function sets a value in member service - * @param _service New value for member service - */ -void sensor_msgs::msg::NavSatStatus::service( - uint16_t _service) -{ - m_service = _service; -} - -/*! - * @brief This function returns the value of member service - * @return Value of member service - */ -uint16_t sensor_msgs::msg::NavSatStatus::service() const -{ - return m_service; -} - -/*! - * @brief This function returns a reference to member service - * @return Reference to member service - */ -uint16_t& sensor_msgs::msg::NavSatStatus::service() -{ - return m_service; -} - -size_t sensor_msgs::msg::NavSatStatus::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_NavSatStatus_max_key_cdr_typesize; -} - -bool sensor_msgs::msg::NavSatStatus::isKeyDefined() -{ - return false; -} - -void sensor_msgs::msg::NavSatStatus::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/NavSatStatus.h b/LibCarla/source/carla/ros2/types/NavSatStatus.h deleted file mode 100644 index df69678aee5..00000000000 --- a/LibCarla/source/carla/ros2/types/NavSatStatus.h +++ /dev/null @@ -1,233 +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 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/types/NavSatStatusPubSubTypes.cpp deleted file mode 100644 index bf6448f16ee..00000000000 --- a/LibCarla/source/carla/ros2/types/NavSatStatusPubSubTypes.cpp +++ /dev/null @@ -1,172 +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.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "NavSatStatusPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace sensor_msgs { - namespace msg { - NavSatStatusPubSubType::NavSatStatusPubSubType() - { - setName("sensor_msgs::msg::dds_::NavSatStatus_"); - auto type_size = NavSatStatus::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = NavSatStatus::isKeyDefined(); - size_t keyLength = NavSatStatus::getKeyMaxCdrSerializedSize() > 16 ? - NavSatStatus::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - NavSatStatusPubSubType::~NavSatStatusPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool NavSatStatusPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - NavSatStatus* 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 NavSatStatusPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - NavSatStatus* 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; - } - - std::function NavSatStatusPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* NavSatStatusPubSubType::createData() - { - return reinterpret_cast(new NavSatStatus()); - } - - void NavSatStatusPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool NavSatStatusPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - NavSatStatus* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - NavSatStatus::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || NavSatStatus::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/types/NavSatStatusPubSubTypes.h b/LibCarla/source/carla/ros2/types/NavSatStatusPubSubTypes.h deleted file mode 100644 index 0ec816ce1f7..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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*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..81387bc25a8 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/Object.h @@ -0,0 +1,351 @@ +// 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/BoundingBox.h" +#include "carla/ros2/types/AcceleratedMovement.h" +#include "carla/ros2/types/AngularVelocity.h" +#include "carla/ros2/types/CoordinateSystemTransform.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/rpc/EnvironmentObject.h" +#include "carla/sensor/data/ActorDynamicState.h" +#include "derived_object_msgs/msg/Object.h" +#include "derived_object_msgs/msg/ObjectWithCovariance.h" +#include "std_msgs/msg/Float32.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_definition( + std::static_pointer_cast(vehicle_actor_definition)) { + + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_OTHER_VEHICLE; + if (actor_definition().base_type == "Bus" || actor_definition().base_type == "Truck" + || actor_definition().base_type == "bus" || actor_definition().base_type == "truck") { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_TRUCK; + } else if (actor_definition().base_type == "car" || actor_definition().base_type == "van") { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_CAR; + } else if (actor_definition().base_type == "motorcycle") { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_MOTORCYCLE; + } else if (actor_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_definition().type_id, "] id: ", actor_definition().id, + " object_type: ", actor_definition().object_type, " base_type: ", actor_definition().base_type, + " mass: ", vehicle_actor_definition->vehicle_physics_control.mass, " estimated ROS-class based on mass: ", classification_string()); + } + } + /** + * 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_definition( + std::static_pointer_cast(walker_actor_definition)) { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_PEDESTRIAN; + carla::log_verbose("Creating Walker Object[", actor_definition().type_id, "] id: ", actor_definition().id, + " object_type: ", actor_definition().object_type, + " base_type: ", actor_definition().base_type, " ROS-class: ", classification_string()); + } + /** + * 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_definition( + std::static_pointer_cast(traffic_light_actor_definition)) { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_SIGN; + carla::log_verbose("Creating Traffic Light Object[", actor_definition().type_id, + "] id: ", actor_definition().id, " object_type: ", actor_definition().object_type, + " base_type: ", actor_definition().base_type, " ROS-class: ", classification_string()); + } + /** + * 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_definition( + std::static_pointer_cast(traffic_sign_actor_definition)) { + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_SIGN; + carla::log_verbose("Creating Traffic Sign Object[", actor_definition().type_id, + "] id: ", actor_definition().id, " object_type: ", actor_definition().object_type, + " base_type: ", actor_definition().base_type, " ROS-class: ", classification_string()); + } + + explicit Object(carla::rpc::EnvironmentObject environment_object, bool enable_for_ros) + : _actor_definition(std::make_shared(environment_object, enable_for_ros)) { + + // derived object msgs are somewhat limited in terms of classification support + // therefore also an actor list for environment objects will be published + // containing the exact tag + switch(environment_object.type) { + case carla::rpc::CityObjectLabel::Pedestrians: + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_PEDESTRIAN; + break; + case carla::rpc::CityObjectLabel::Rider: + case carla::rpc::CityObjectLabel::Bicycle: + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_BIKE; + break; + case carla::rpc::CityObjectLabel::Car: + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_CAR; + break; + case carla::rpc::CityObjectLabel::Motorcycle: + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_MOTORCYCLE; + break; + case carla::rpc::CityObjectLabel::Bus: + case carla::rpc::CityObjectLabel::Truck: + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_TRUCK; + break; + case carla::rpc::CityObjectLabel::TrafficLight: + case carla::rpc::CityObjectLabel::TrafficSigns: + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_SIGN; + break; + case carla::rpc::CityObjectLabel::Train: + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_OTHER_VEHICLE; + break; + case carla::rpc::CityObjectLabel::Poles: + case carla::rpc::CityObjectLabel::Fences: + case carla::rpc::CityObjectLabel::Walls: + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_BARRIER; + break; + case carla::rpc::CityObjectLabel::Buildings: + case carla::rpc::CityObjectLabel::Static: + default: + _classification = derived_object_msgs::msg::Object_Constants::CLASSIFICATION_UNKNOWN; + } + + // and put in our object state update + carla::sensor::data::ActorDynamicState actor_dynamic_state; + actor_dynamic_state.id = actor_id(); + // environment objects have a 64 bit unreal id, but Object.msg only supports uint32, + // so we put the upper 32 bit of the actor id into the classification age, + // so that we can correlate the object in the object list with the 64-bit id in the CarlaActorInfo list for environment objects + _classification_age = static_cast((actor_definition().id>>32) & 0xFFFFFFFF); + _actor_definition->attributes["Object.id"] = std::to_string(actor_id()); + _actor_definition->attributes["Object.classification_age"] = std::to_string(_classification_age); + actor_dynamic_state.transform = environment_object.transform; + actor_dynamic_state.quaternion = carla::geom::Quaternion(environment_object.transform.rotation); + // make the bounding box location relative to the object transform + _actor_definition->bounding_box.location = actor_definition().bounding_box.location - environment_object.transform.location; + _actor_definition->bounding_box.rotation = carla::geom::Rotation(); + UpdateObject(carla::ros2::types::Timestamp(), actor_dynamic_state); + carla::log_verbose("Creating Environment Object[", actor_definition().type_id, + "] id: ", actor_id(), " object_type: ", actor_definition().object_type, + " base_type: ", actor_definition().base_type, " ROS-class: ", classification_string(), " Bounding Box Location ", _actor_definition->bounding_box.location); + } + + ~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) { + _transform = carla::ros2::types::Transform(actor_dynamic_state.transform, actor_dynamic_state.quaternion); + _accelerated_movement.Update( + carla::geom::Velocity(actor_dynamic_state.velocity), + AngularVelocity(actor_dynamic_state.angular_velocity, AngularVelocity::AngularVelocityMode::DEGREE), + carla::geom::Acceleration(actor_dynamic_state.acceleration), + actor_dynamic_state.quaternion, + timestamp); + } + + 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_id()); + object.detection_level(derived_object_msgs::msg::Object_Constants::OBJECT_TRACKED); + object.object_classified(true); + object.pose(get_center_pose()); + object.twist(_accelerated_movement.absolute_twist()); + object.accel(_accelerated_movement.absolute_accel()); + object.shape().type(shape_msgs::msg::SolidPrimitive_Constants::BOX); + auto const ros_extent = actor_definition().bounding_box.extent * 2.f; + object.shape().dimensions({ros_extent.x, ros_extent.y, ros_extent.z}); + auto bounding_box_relative_to_pose = actor_definition().bounding_box; + bounding_box_relative_to_pose.location = carla::geom::Location(); + object.shape().polygon().points(*Polygon(bounding_box_relative_to_pose.GetLocalVertices()).polygon()); + 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_id()); + object.detection_level(derived_object_msgs::msg::Object_Constants::OBJECT_TRACKED); + object.object_classified(true); + object.pose(get_center_pose_with_covariance()); + object.twist(_accelerated_movement.absolute_twist_with_covariance()); + object.accel(_accelerated_movement.absolute_accel_with_covariance()); + object.shape().type(shape_msgs::msg::SolidPrimitive_Constants::BOX); + auto const ros_extent = actor_definition().bounding_box.extent * 2.f; + object.shape().dimensions({ros_extent.x, ros_extent.y, ros_extent.z}); + object.classification(_classification); + object.classification_certainty(255u); + object.classification_age(_classification_age); + return object; + } + + geometry_msgs::msg::Pose get_center_pose() const { + auto ros_pose=_transform.pose(); + // the pose is the transform of the object reference point, the center of the bounding box + // might be shifted (usually half the height upwards) + auto center_offset = CoordinateSystemTransform::TransformLinearAxisMsg(actor_definition().bounding_box.location); + ros_pose.position().x(ros_pose.position().x() + center_offset.x()); + ros_pose.position().y(ros_pose.position().y() + center_offset.y()); + ros_pose.position().z(ros_pose.position().z() + center_offset.z()); + return ros_pose; + } + + geometry_msgs::msg::PoseWithCovariance get_center_pose_with_covariance() const { + geometry_msgs::msg::PoseWithCovariance ros_pose_with_covariance; + ros_pose_with_covariance.pose(get_center_pose()); + return ros_pose_with_covariance; + } + + + + + /** + * @brief check if dynamic content has changed (ignoring timestamp) + */ + bool has_dynamic_data_changed(derived_object_msgs::msg::Object const &other) const { + return (other.id()!=actor_definition().id) + || (other.pose() != _transform.pose()) + || (other.twist() != _accelerated_movement.absolute_twist()) + || (other.accel() != _accelerated_movement.absolute_accel()); + } + + + /** + * The resulting ROS std_msgs::msg::Float32 + */ + std_msgs::msg::Float32 speed() const { + std_msgs::msg::Float32 ros_speed; + ros_speed.data(_accelerated_movement.LinearVelocity().Speed(_transform.GetQuaternion())); + return ros_speed; + } + + + carla::ros2::types::Timestamp const& Timestamp() const { + return _accelerated_movement.Timestamp(); + } + + carla::ros2::types::Transform const& Transform() const { + return _transform; + } + + carla::ros2::types::AcceleratedMovement const& AcceleratedMovement() const { + return _accelerated_movement; + } + + uint8_t classification() const { + return _classification; + } + + std::string classification_string() const { + switch (_classification) { + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_UNKNOWN: + return "UNKNOWN"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_UNKNOWN_SMALL: + return "UNKNOWN_SMALL"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_UNKNOWN_MEDIUM: + return "UNKNOWN_MEDIUM"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_UNKNOWN_BIG: + return "UNKNOWN_BIG"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_PEDESTRIAN: + return "PEDESTRIAN"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_BIKE: + return "BIKE"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_CAR: + return "CAR"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_TRUCK: + return "TRUCK"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_MOTORCYCLE: + return "MOTORCYCLE"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_OTHER_VEHICLE: + return "OTHER_VEHICLE"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_BARRIER: + return "BARRIER"; + case derived_object_msgs::msg::Object_Constants::CLASSIFICATION_SIGN: + return "SIGN"; + default: + return "N/A"; + } + } + + carla_msgs::msg::CarlaActorInfo carla_actor_info(std::shared_ptr name_registry = nullptr) const { + return actor_definition().carla_actor_info(name_registry); + } + + carla::streaming::detail::actor_id_type actor_id() const { + return static_cast(actor_definition().id & 0xFFFFFFFF); } + + const carla::ros2::types::ActorDefinition& actor_definition()const { return *_actor_definition; } + + const carla::ros2::types::ActorNameDefinition& actor_name_definition()const { return *_actor_definition; } + +private: + std::shared_ptr _actor_definition; + uint8_t _classification{derived_object_msgs::msg::Object_Constants::CLASSIFICATION_UNKNOWN}; + carla::ros2::types::Transform _transform; + carla::ros2::types::AcceleratedMovement _accelerated_movement; + uint32_t _classification_age{std::numeric_limits::max()}; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/Odometry.cpp b/LibCarla/source/carla/ros2/types/Odometry.cpp deleted file mode 100644 index ce1fd661536..00000000000 --- a/LibCarla/source/carla/ros2/types/Odometry.cpp +++ /dev/null @@ -1,330 +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 Odometry.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 "Odometry.h" -#include - -#include -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_Pose_max_cdr_typesize 56ULL; -#define std_msgs_msg_Time_max_cdr_typesize 8ULL; -#define nav_msgs_msg_Odometry_max_cdr_typesize 1208ULL; -#define geometry_msgs_msg_Twist_max_cdr_typesize 48ULL; -#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 std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define geometry_msgs_msg_TwistWithCovariance_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Pose_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Time_max_key_cdr_typesize 0ULL; -#define nav_msgs_msg_Odometry_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Twist_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; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; - -nav_msgs::msg::Odometry::Odometry() -{ - // std_msgs::msg::Header m_header - - // string m_child_frame_id - m_child_frame_id =""; - // geometry_msgs::msg::PoseWithCovariance m_pose - - // geometry_msgs::msg::TwistWithCovariance m_twist -} - -nav_msgs::msg::Odometry::~Odometry() -{ -} - -nav_msgs::msg::Odometry::Odometry( - const Odometry& x) -{ - m_header = x.m_header; - m_child_frame_id = x.m_child_frame_id; - m_pose = x.m_pose; - m_twist = x.m_twist; -} - -nav_msgs::msg::Odometry::Odometry( - Odometry&& x) noexcept -{ - m_header = std::move(x.m_header); - m_child_frame_id = std::move(x.m_child_frame_id); - m_pose = std::move(x.m_pose); - m_twist = std::move(x.m_twist); -} - -nav_msgs::msg::Odometry& nav_msgs::msg::Odometry::operator =( - const Odometry& x) -{ - m_header = x.m_header; - m_child_frame_id = x.m_child_frame_id; - m_pose = x.m_pose; - m_twist = x.m_twist; - - return *this; -} - -nav_msgs::msg::Odometry& nav_msgs::msg::Odometry::operator =( - Odometry&& x) noexcept -{ - m_header = std::move(x.m_header); - m_child_frame_id = std::move(x.m_child_frame_id); - m_pose = std::move(x.m_pose); - m_twist = std::move(x.m_twist); - - return *this; -} - -bool nav_msgs::msg::Odometry::operator ==( - const Odometry& x) const -{ - return (m_header == x.m_header && m_child_frame_id == x.m_child_frame_id && m_pose == x.m_pose && m_twist == x.m_twist); -} - -bool nav_msgs::msg::Odometry::operator !=( - const Odometry& x) const -{ - return !(*this == x); -} - -size_t nav_msgs::msg::Odometry::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return nav_msgs_msg_Odometry_max_cdr_typesize; -} - -size_t nav_msgs::msg::Odometry::getCdrSerializedSize( - const nav_msgs::msg::Odometry& 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) + data.child_frame_id().size() + 1; - current_alignment += geometry_msgs::msg::PoseWithCovariance::getCdrSerializedSize(data.pose(), current_alignment); - current_alignment += geometry_msgs::msg::TwistWithCovariance::getCdrSerializedSize(data.twist(), current_alignment); - - return current_alignment - initial_alignment; -} - -void nav_msgs::msg::Odometry::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_header; - scdr << m_child_frame_id.c_str(); - scdr << m_pose; - scdr << m_twist; -} - -void nav_msgs::msg::Odometry::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_header; - dcdr >> m_child_frame_id; - dcdr >> m_pose; - dcdr >> m_twist; -} - -/*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ -void nav_msgs::msg::Odometry::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 nav_msgs::msg::Odometry::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& nav_msgs::msg::Odometry::header() const -{ - return m_header; -} - -/*! - * @brief This function returns a reference to member header - * @return Reference to member header - */ -std_msgs::msg::Header& nav_msgs::msg::Odometry::header() -{ - return m_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 - */ -void nav_msgs::msg::Odometry::child_frame_id( - const std::string& _child_frame_id) -{ - m_child_frame_id = _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 - */ -void nav_msgs::msg::Odometry::child_frame_id( - std::string&& _child_frame_id) -{ - m_child_frame_id = std::move(_child_frame_id); -} - -/*! - * @brief This function returns a constant reference to member child_frame_id - * @return Constant reference to member child_frame_id - */ -const std::string& nav_msgs::msg::Odometry::child_frame_id() const -{ - return m_child_frame_id; -} - -/*! - * @brief This function returns a reference to member child_frame_id - * @return Reference to member child_frame_id - */ -std::string& nav_msgs::msg::Odometry::child_frame_id() -{ - return m_child_frame_id; -} - -/*! - * @brief This function copies the value in member pose - * @param _pose New value to be copied in member pose - */ -void nav_msgs::msg::Odometry::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 nav_msgs::msg::Odometry::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& nav_msgs::msg::Odometry::pose() const -{ - return m_pose; -} - -/*! - * @brief This function returns a reference to member pose - * @return Reference to member pose - */ -geometry_msgs::msg::PoseWithCovariance& nav_msgs::msg::Odometry::pose() -{ - return m_pose; -} - -/*! - * @brief This function copies the value in member twist - * @param _twist New value to be copied in member twist - */ -void nav_msgs::msg::Odometry::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 nav_msgs::msg::Odometry::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& nav_msgs::msg::Odometry::twist() const -{ - return m_twist; -} - -/*! - * @brief This function returns a reference to member twist - * @return Reference to member twist - */ -geometry_msgs::msg::TwistWithCovariance& nav_msgs::msg::Odometry::twist() -{ - return m_twist; -} - -size_t nav_msgs::msg::Odometry::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return nav_msgs_msg_Odometry_max_key_cdr_typesize; -} - -bool nav_msgs::msg::Odometry::isKeyDefined() -{ - return false; -} - -void nav_msgs::msg::Odometry::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/Odometry.h b/LibCarla/source/carla/ros2/types/Odometry.h deleted file mode 100644 index fe33619e665..00000000000 --- a/LibCarla/source/carla/ros2/types/Odometry.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 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 "PoseWithCovariance.h" -#include "TwistWithCovariance.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(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/types/OdometryPubSubTypes.cpp deleted file mode 100644 index 836c765a133..00000000000 --- a/LibCarla/source/carla/ros2/types/OdometryPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 OdometryPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "OdometryPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace nav_msgs { - namespace msg { - OdometryPubSubType::OdometryPubSubType() - { - setName("nav_msgs::msg::dds_::Odometry_"); - auto type_size = Odometry::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Odometry::isKeyDefined(); - size_t keyLength = Odometry::getKeyMaxCdrSerializedSize() > 16 ? - Odometry::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - OdometryPubSubType::~OdometryPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool OdometryPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Odometry* 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 OdometryPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - Odometry* 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; - } - - std::function OdometryPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* OdometryPubSubType::createData() - { - return reinterpret_cast(new Odometry()); - } - - void OdometryPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool OdometryPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Odometry* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Odometry::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Odometry::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 nav_msgs diff --git a/LibCarla/source/carla/ros2/types/OdometryPubSubTypes.h b/LibCarla/source/carla/ros2/types/OdometryPubSubTypes.h deleted file mode 100644 index 2c333fe0cf1..00000000000 --- a/LibCarla/source/carla/ros2/types/OdometryPubSubTypes.h +++ /dev/null @@ -1,109 +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 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 "PoseWithCovariancePubSubTypes.h" -#include "TwistWithCovariancePubSubTypes.h" -#include "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; - }; - } -} - -#endif // _FAST_DDS_GENERATED_NAV_MSGS_MSG_ODOMETRY_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Point.cpp b/LibCarla/source/carla/ros2/types/Point.cpp deleted file mode 100644 index ddb8fba9d85..00000000000 --- a/LibCarla/source/carla/ros2/types/Point.cpp +++ /dev/null @@ -1,238 +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 Point.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 "Point.h" -#include - -#include -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 = 0.0; - // double m_y - m_y = 0.0; - // double m_z - m_z = 0.0; -} - -geometry_msgs::msg::Point::~Point() -{ -} - -geometry_msgs::msg::Point::Point( - const Point& x) -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; -} - -geometry_msgs::msg::Point::Point( - Point&& x) noexcept -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; -} - -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; - - return *this; -} - -geometry_msgs::msg::Point& geometry_msgs::msg::Point::operator =( - Point&& x) noexcept -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; - - return *this; -} - -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); -} - -bool geometry_msgs::msg::Point::operator !=( - const Point& x) const -{ - return !(*this == x); -} - -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 geometry_msgs::msg::Point::getCdrSerializedSize( - const geometry_msgs::msg::Point& data, - size_t current_alignment) -{ - (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; -} - -/*! - * @brief This function sets a value in member x - * @param _x New value for member x - */ -void geometry_msgs::msg::Point::x( - double _x) -{ - m_x = _x; -} - -/*! - * @brief This function returns the value of member x - * @return Value of member x - */ -double geometry_msgs::msg::Point::x() const -{ - return m_x; -} - -/*! - * @brief This function returns a reference to member x - * @return Reference to member x - */ -double& geometry_msgs::msg::Point::x() -{ - return m_x; -} - -/*! - * @brief This function sets a value in member y - * @param _y New value for member y - */ -void geometry_msgs::msg::Point::y( - double _y) -{ - m_y = _y; -} - -/*! - * @brief This function returns the value of member y - * @return Value of member y - */ -double geometry_msgs::msg::Point::y() const -{ - return m_y; -} - -/*! - * @brief This function returns a reference to member y - * @return Reference to member y - */ -double& geometry_msgs::msg::Point::y() -{ - return m_y; -} - -/*! - * @brief This function sets a value in member z - * @param _z New value for member z - */ -void geometry_msgs::msg::Point::z( - double _z) -{ - m_z = _z; -} - -/*! - * @brief This function returns the value of member z - * @return Value of member z - */ -double geometry_msgs::msg::Point::z() const -{ - return m_z; -} - -/*! - * @brief This function returns a reference to member z - * @return Reference to member z - */ -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; -} - -bool geometry_msgs::msg::Point::isKeyDefined() -{ - return false; -} - -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/types/Point.h deleted file mode 100644 index 016955ff318..00000000000 --- a/LibCarla/source/carla/ros2/types/Point.h +++ /dev/null @@ -1,245 +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 Point.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_POINT_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_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(Point_SOURCE) -#define Point_DllAPI __declspec( dllexport ) -#else -#define Point_DllAPI __declspec( dllimport ) -#endif // Point_SOURCE -#else -#define Point_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define Point_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace geometry_msgs { - namespace msg { - /*! - * @brief This class represents the structure Point defined by the user in the IDL file. - * @ingroup POINT - */ - class Point - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Point(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Point(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object geometry_msgs::msg::Point that will be copied. - */ - eProsima_user_DllExport Point( - const Point& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object geometry_msgs::msg::Point that will be copied. - */ - eProsima_user_DllExport Point( - Point&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object geometry_msgs::msg::Point that will be copied. - */ - eProsima_user_DllExport Point& operator =( - const Point& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object geometry_msgs::msg::Point that will be copied. - */ - eProsima_user_DllExport Point& operator =( - Point&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Point object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Point& x) const; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Point object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Point& 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 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::Point& 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; - }; - } // namespace msg -} // namespace geometry_msgs - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_H_ diff --git a/LibCarla/source/carla/ros2/types/Point32.cpp b/LibCarla/source/carla/ros2/types/Point32.cpp deleted file mode 100644 index 0aa824cb038..00000000000 --- a/LibCarla/source/carla/ros2/types/Point32.cpp +++ /dev/null @@ -1,238 +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 Point32.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 "Point32.h" -#include - -#include -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 = 0.0; - // float m_y - m_y = 0.0; - // float m_z - m_z = 0.0; -} - -geometry_msgs::msg::Point32::~Point32() -{ -} - -geometry_msgs::msg::Point32::Point32( - const Point32& x) -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; -} - -geometry_msgs::msg::Point32::Point32( - Point32&& x) noexcept -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; -} - -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; - - return *this; -} - -geometry_msgs::msg::Point32& geometry_msgs::msg::Point32::operator =( - Point32&& x) noexcept -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; - - return *this; -} - -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); -} - -bool geometry_msgs::msg::Point32::operator !=( - const Point32& x) const -{ - return !(*this == x); -} - -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 geometry_msgs::msg::Point32::getCdrSerializedSize( - const geometry_msgs::msg::Point32& 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); - - 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; -} - -/*! - * @brief This function sets a value in member x - * @param _x New value for member x - */ -void geometry_msgs::msg::Point32::x( - float _x) -{ - m_x = _x; -} - -/*! - * @brief This function returns the value of member x - * @return Value of member x - */ -float geometry_msgs::msg::Point32::x() const -{ - return m_x; -} - -/*! - * @brief This function returns a reference to member x - * @return Reference to member x - */ -float& geometry_msgs::msg::Point32::x() -{ - return m_x; -} - -/*! - * @brief This function sets a value in member y - * @param _y New value for member y - */ -void geometry_msgs::msg::Point32::y( - float _y) -{ - m_y = _y; -} - -/*! - * @brief This function returns the value of member y - * @return Value of member y - */ -float geometry_msgs::msg::Point32::y() const -{ - return m_y; -} - -/*! - * @brief This function returns a reference to member y - * @return Reference to member y - */ -float& geometry_msgs::msg::Point32::y() -{ - return m_y; -} - -/*! - * @brief This function sets a value in member z - * @param _z New value for member z - */ -void geometry_msgs::msg::Point32::z( - float _z) -{ - m_z = _z; -} - -/*! - * @brief This function returns the value of member z - * @return Value of member z - */ -float geometry_msgs::msg::Point32::z() const -{ - return m_z; -} - -/*! - * @brief This function returns a reference to member z - * @return Reference to member z - */ -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; -} - -bool geometry_msgs::msg::Point32::isKeyDefined() -{ - return false; -} - -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/types/Point32.h deleted file mode 100644 index fbadcc6da30..00000000000 --- a/LibCarla/source/carla/ros2/types/Point32.h +++ /dev/null @@ -1,245 +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 Point32.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_POINT32_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_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(Point32_SOURCE) -#define Point32_DllAPI __declspec( dllexport ) -#else -#define Point32_DllAPI __declspec( dllimport ) -#endif // Point32_SOURCE -#else -#define Point32_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define Point32_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace geometry_msgs { - namespace msg { - /*! - * @brief This class represents the structure Point32 defined by the user in the IDL file. - * @ingroup POINT32 - */ - class Point32 - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Point32(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Point32(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object geometry_msgs::msg::Point32 that will be copied. - */ - eProsima_user_DllExport Point32( - const Point32& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object geometry_msgs::msg::Point32 that will be copied. - */ - eProsima_user_DllExport Point32( - Point32&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object geometry_msgs::msg::Point32 that will be copied. - */ - eProsima_user_DllExport Point32& operator =( - const Point32& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object geometry_msgs::msg::Point32 that will be copied. - */ - eProsima_user_DllExport Point32& operator =( - Point32&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Point32 object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Point32& x) const; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Point32 object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Point32& x) const; - - /*! - * @brief This function sets a value in member x - * @param _x New value for member x - */ - eProsima_user_DllExport void x( - float _x); - - /*! - * @brief This function returns the value of member x - * @return Value of member x - */ - eProsima_user_DllExport float x() const; - - /*! - * @brief This function returns a reference to member x - * @return Reference to member x - */ - eProsima_user_DllExport float& x(); - - /*! - * @brief This function sets a value in member y - * @param _y New value for member y - */ - eProsima_user_DllExport void y( - float _y); - - /*! - * @brief This function returns the value of member y - * @return Value of member y - */ - eProsima_user_DllExport float y() const; - - /*! - * @brief This function returns a reference to member y - * @return Reference to member y - */ - eProsima_user_DllExport float& y(); - - /*! - * @brief This function sets a value in member z - * @param _z New value for member z - */ - eProsima_user_DllExport void z( - float _z); - - /*! - * @brief This function returns the value of member z - * @return Value of member z - */ - eProsima_user_DllExport float z() const; - - /*! - * @brief This function returns a reference to member z - * @return Reference to member z - */ - 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. - */ - 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::Point32& 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_x; - float m_y; - float m_z; - }; - } // namespace msg -} // namespace geometry_msgs - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_H_ diff --git a/LibCarla/source/carla/ros2/types/Point32PubSubTypes.cpp b/LibCarla/source/carla/ros2/types/Point32PubSubTypes.cpp deleted file mode 100644 index 8d852bee7c9..00000000000 --- a/LibCarla/source/carla/ros2/types/Point32PubSubTypes.cpp +++ /dev/null @@ -1,172 +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 Point32PubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "Point32PubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace geometry_msgs { - namespace msg { - Point32PubSubType::Point32PubSubType() - { - setName("geometry_msgs::msg::dds_::Point32_"); - auto type_size = Point32::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Point32::isKeyDefined(); - size_t keyLength = Point32::getKeyMaxCdrSerializedSize() > 16 ? - Point32::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - Point32PubSubType::~Point32PubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool Point32PubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Point32* 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 Point32PubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //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 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; - } - - std::function Point32PubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* Point32PubSubType::createData() - { - return reinterpret_cast(new Point32()); - } - - void Point32PubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool Point32PubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Point32* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Point32::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Point32::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/Point32PubSubTypes.h b/LibCarla/source/carla/ros2/types/Point32PubSubTypes.h deleted file mode 100644 index 8fffbc648d1..00000000000 --- a/LibCarla/source/carla/ros2/types/Point32PubSubTypes.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 Point32PubSubTypes.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_POINT32_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_PUBSUBTYPES_H_ - -#include -#include - -#include "Point32.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated Point32 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 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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type Point32 defined by the user in the IDL file. - * @ingroup POINT32 - */ - class Point32PubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef Point32 type; - - eProsima_user_DllExport Point32PubSubType(); - - eProsima_user_DllExport virtual ~Point32PubSubType() 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) Point32(); - 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 12ULL == (detail::Point32_offset_of() + sizeof(float)); - }}; - } -} - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT32_PUBSUBTYPES_H_ 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/PointCloud2.h b/LibCarla/source/carla/ros2/types/PointCloud2.h deleted file mode 100644 index 8a4734a917b..00000000000 --- a/LibCarla/source/carla/ros2/types/PointCloud2.h +++ /dev/null @@ -1,386 +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.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 "Header.h" -#include "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(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 PointCloud2 defined by the user in the IDL file. - * @ingroup POINTCLOUD2 - */ - class PointCloud2 - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport PointCloud2(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~PointCloud2(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. - */ - eProsima_user_DllExport PointCloud2( - const PointCloud2& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. - */ - eProsima_user_DllExport PointCloud2( - PointCloud2&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. - */ - eProsima_user_DllExport PointCloud2& operator =( - const PointCloud2& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object sensor_msgs::msg::PointCloud2 that will be copied. - */ - eProsima_user_DllExport PointCloud2& operator =( - PointCloud2&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::PointCloud2 object to compare. - */ - eProsima_user_DllExport bool operator ==( - const PointCloud2& x) const; - - /*! - * @brief Comparison operator. - * @param x sensor_msgs::msg::PointCloud2 object to compare. - */ - eProsima_user_DllExport bool operator !=( - const PointCloud2& 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 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 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::PointCloud2& 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; - std::vector m_data; - bool m_is_dense; - }; - } // namespace msg -} // namespace sensor_msgs - -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTCLOUD2_H_ diff --git a/LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.cpp b/LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.cpp deleted file mode 100644 index d2e39c66dc9..00000000000 --- a/LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.cpp +++ /dev/null @@ -1,172 +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 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 { - PointCloud2PubSubType::PointCloud2PubSubType() - { - setName("sensor_msgs::msg::dds_::PointCloud2_"); - auto type_size = PointCloud2::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_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - PointCloud2PubSubType::~PointCloud2PubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool PointCloud2PubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - PointCloud2* 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 PointCloud2PubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - PointCloud2* 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; - } - - std::function PointCloud2PubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* PointCloud2PubSubType::createData() - { - return reinterpret_cast(new PointCloud2()); - } - - void PointCloud2PubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool PointCloud2PubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - PointCloud2* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - PointCloud2::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) - { - 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/types/PointCloud2PubSubTypes.h b/LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.h deleted file mode 100644 index 3fe6150ed01..00000000000 --- a/LibCarla/source/carla/ros2/types/PointCloud2PubSubTypes.h +++ /dev/null @@ -1,109 +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 PointCloud2PubSubTypes.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 "HeaderPubSubTypes.h" -#include "PointFieldPubSubTypes.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 - */ - class PointCloud2PubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef PointCloud2 type; - - eProsima_user_DllExport PointCloud2PubSubType(); - - eProsima_user_DllExport virtual ~PointCloud2PubSubType() 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; - }; - } -} - -#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/types/PointField.cpp deleted file mode 100644 index 9bc2e3fd7a9..00000000000 --- a/LibCarla/source/carla/ros2/types/PointField.cpp +++ /dev/null @@ -1,284 +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 PointField.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 "PointField.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define sensor_msgs_msg_PointField_max_cdr_typesize 272ULL; -#define sensor_msgs_msg_PointField_max_key_cdr_typesize 0ULL; - -sensor_msgs::msg::PointField::PointField() -{ - // string m_name - m_name =""; - // unsigned long m_offset - m_offset = 0; - // octet m_datatype - m_datatype = 0; - // unsigned long m_count - m_count = 0; -} - -sensor_msgs::msg::PointField::~PointField() -{ -} - -sensor_msgs::msg::PointField::PointField( - const PointField& x) -{ - m_name = x.m_name; - m_offset = x.m_offset; - m_datatype = x.m_datatype; - m_count = x.m_count; -} - -sensor_msgs::msg::PointField::PointField( - PointField&& x) noexcept -{ - m_name = std::move(x.m_name); - m_offset = x.m_offset; - m_datatype = x.m_datatype; - m_count = x.m_count; -} - -sensor_msgs::msg::PointField& sensor_msgs::msg::PointField::operator =( - const PointField& x) -{ - m_name = x.m_name; - m_offset = x.m_offset; - m_datatype = x.m_datatype; - m_count = x.m_count; - - return *this; -} - -sensor_msgs::msg::PointField& sensor_msgs::msg::PointField::operator =( - PointField&& x) noexcept -{ - m_name = std::move(x.m_name); - m_offset = x.m_offset; - m_datatype = x.m_datatype; - m_count = x.m_count; - - return *this; -} - -bool sensor_msgs::msg::PointField::operator ==( - const PointField& x) const -{ - return (m_name == x.m_name && m_offset == x.m_offset && m_datatype == x.m_datatype && m_count == x.m_count); -} - -bool sensor_msgs::msg::PointField::operator !=( - const PointField& x) const -{ - return !(*this == x); -} - -size_t sensor_msgs::msg::PointField::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_PointField_max_cdr_typesize; -} - -size_t sensor_msgs::msg::PointField::getCdrSerializedSize( - const sensor_msgs::msg::PointField& data, - size_t current_alignment) -{ - size_t initial_alignment = current_alignment; - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.name().size() + 1; - 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); - - return current_alignment - initial_alignment; -} - -void sensor_msgs::msg::PointField::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_name.c_str(); - scdr << m_offset; - scdr << m_datatype; - scdr << m_count; -} - -void sensor_msgs::msg::PointField::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_name; - dcdr >> m_offset; - dcdr >> m_datatype; - dcdr >> m_count; -} - -/*! - * @brief This function copies the value in member name - * @param _name New value to be copied in member name - */ -void sensor_msgs::msg::PointField::name( - const std::string& _name) -{ - m_name = _name; -} - -/*! - * @brief This function moves the value in member name - * @param _name New value to be moved in member name - */ -void sensor_msgs::msg::PointField::name( - std::string&& _name) -{ - m_name = std::move(_name); -} - -/*! - * @brief This function returns a constant reference to member name - * @return Constant reference to member name - */ -const std::string& sensor_msgs::msg::PointField::name() const -{ - return m_name; -} - -/*! - * @brief This function returns a reference to member name - * @return Reference to member name - */ -std::string& sensor_msgs::msg::PointField::name() -{ - return m_name; -} - -/*! - * @brief This function sets a value in member offset - * @param _offset New value for member offset - */ -void sensor_msgs::msg::PointField::offset( - uint32_t _offset) -{ - m_offset = _offset; -} - -/*! - * @brief This function returns the value of member offset - * @return Value of member offset - */ -uint32_t sensor_msgs::msg::PointField::offset() const -{ - return m_offset; -} - -/*! - * @brief This function returns a reference to member offset - * @return Reference to member offset - */ -uint32_t& sensor_msgs::msg::PointField::offset() -{ - return m_offset; -} - -/*! - * @brief This function sets a value in member datatype - * @param _datatype New value for member datatype - */ -void sensor_msgs::msg::PointField::datatype( - uint8_t _datatype) -{ - m_datatype = _datatype; -} - -/*! - * @brief This function returns the value of member datatype - * @return Value of member datatype - */ -uint8_t sensor_msgs::msg::PointField::datatype() const -{ - return m_datatype; -} - -/*! - * @brief This function returns a reference to member datatype - * @return Reference to member datatype - */ -uint8_t& sensor_msgs::msg::PointField::datatype() -{ - return m_datatype; -} - -/*! - * @brief This function sets a value in member count - * @param _count New value for member count - */ -void sensor_msgs::msg::PointField::count( - uint32_t _count) -{ - m_count = _count; -} - -/*! - * @brief This function returns the value of member count - * @return Value of member count - */ -uint32_t sensor_msgs::msg::PointField::count() const -{ - return m_count; -} - -/*! - * @brief This function returns a reference to member count - * @return Reference to member count - */ -uint32_t& sensor_msgs::msg::PointField::count() -{ - return m_count; -} - -size_t sensor_msgs::msg::PointField::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_PointField_max_key_cdr_typesize; -} - -bool sensor_msgs::msg::PointField::isKeyDefined() -{ - return false; -} - -void sensor_msgs::msg::PointField::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/PointField.h b/LibCarla/source/carla/ros2/types/PointField.h deleted file mode 100644 index 16be2f69924..00000000000 --- a/LibCarla/source/carla/ros2/types/PointField.h +++ /dev/null @@ -1,281 +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 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/types/PointFieldPubSubTypes.cpp deleted file mode 100644 index 8b7587dcfee..00000000000 --- a/LibCarla/source/carla/ros2/types/PointFieldPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 PointFieldPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "PointFieldPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace sensor_msgs { - namespace msg { - PointFieldPubSubType::PointFieldPubSubType() - { - setName("sensor_msgs::msg::dds_::PointField_"); - auto type_size = PointField::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = PointField::isKeyDefined(); - size_t keyLength = PointField::getKeyMaxCdrSerializedSize() > 16 ? - PointField::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - PointFieldPubSubType::~PointFieldPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool PointFieldPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - PointField* 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 PointFieldPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - PointField* 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; - } - - std::function PointFieldPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* PointFieldPubSubType::createData() - { - return reinterpret_cast(new PointField()); - } - - void PointFieldPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool PointFieldPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - PointField* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - PointField::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || PointField::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/types/PointFieldPubSubTypes.h b/LibCarla/source/carla/ros2/types/PointFieldPubSubTypes.h deleted file mode 100644 index 1ff3d73c430..00000000000 --- a/LibCarla/source/carla/ros2/types/PointFieldPubSubTypes.h +++ /dev/null @@ -1,105 +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 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; - }; - } -} - -#endif // _FAST_DDS_GENERATED_SENSOR_MSGS_MSG_POINTFIELD_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/PointPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/PointPubSubTypes.cpp deleted file mode 100644 index cd97d27192d..00000000000 --- a/LibCarla/source/carla/ros2/types/PointPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 PointPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "PointPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace geometry_msgs { - namespace msg { - PointPubSubType::PointPubSubType() - { - setName("geometry_msgs::msg::dds_::Point_"); - auto type_size = Point::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Point::isKeyDefined(); - size_t keyLength = Point::getKeyMaxCdrSerializedSize() > 16 ? - Point::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - PointPubSubType::~PointPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool PointPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Point* 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 PointPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //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 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; - } - - std::function PointPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* PointPubSubType::createData() - { - return reinterpret_cast(new Point()); - } - - void PointPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool PointPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Point* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Point::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Point::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/PointPubSubTypes.h b/LibCarla/source/carla/ros2/types/PointPubSubTypes.h deleted file mode 100644 index 0f42f2d3b38..00000000000 --- a/LibCarla/source/carla/ros2/types/PointPubSubTypes.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 PointPubSubTypes.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_POINT_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_PUBSUBTYPES_H_ - -#include -#include - -#include "Point.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated Point 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 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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type Point defined by the user in the IDL file. - * @ingroup POINT - */ - class PointPubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef Point type; - - eProsima_user_DllExport PointPubSubType(); - - eProsima_user_DllExport virtual ~PointPubSubType() 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) Point(); - 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 24ULL == (detail::Point_offset_of() + sizeof(double)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POINT_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Polygon.h b/LibCarla/source/carla/ros2/types/Polygon.h new file mode 100644 index 00000000000..8b90481c927 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/Polygon.h @@ -0,0 +1,65 @@ +// 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/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)); + } + } + + Polygon(std::vector const &vertices) + : _ros_polygon(std::make_shared>()) { + _ros_polygon->reserve(vertices.size()); + for (auto const &vertex : vertices) { + _ros_polygon->push_back(CoordinateSystemTransform::TransformLocationToPoint32Msg(vertex)); + } + } + + ~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/Pose.cpp b/LibCarla/source/carla/ros2/types/Pose.cpp deleted file mode 100644 index d643cd126ec..00000000000 --- a/LibCarla/source/carla/ros2/types/Pose.cpp +++ /dev/null @@ -1,221 +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 Pose.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 "Pose.h" -#include - -#include -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() -{ -} - -geometry_msgs::msg::Pose::~Pose() -{ -} - -geometry_msgs::msg::Pose::Pose( - const Pose& x) -{ - m_position = x.m_position; - m_orientation = x.m_orientation; -} - -geometry_msgs::msg::Pose::Pose( - Pose&& x) noexcept -{ - m_position = std::move(x.m_position); - m_orientation = std::move(x.m_orientation); -} - -geometry_msgs::msg::Pose& geometry_msgs::msg::Pose::operator =( - const Pose& x) -{ - m_position = x.m_position; - m_orientation = x.m_orientation; - - return *this; -} - -geometry_msgs::msg::Pose& geometry_msgs::msg::Pose::operator =( - Pose&& x) noexcept -{ - m_position = std::move(x.m_position); - m_orientation = std::move(x.m_orientation); - - return *this; -} - -bool geometry_msgs::msg::Pose::operator ==( - const Pose& x) const -{ - return (m_position == x.m_position && m_orientation == x.m_orientation); -} - -bool geometry_msgs::msg::Pose::operator !=( - const Pose& x) const -{ - return !(*this == x); -} - -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 geometry_msgs::msg::Pose::getCdrSerializedSize( - const geometry_msgs::msg::Pose& data, - size_t current_alignment) -{ - 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); - - return current_alignment - initial_alignment; -} - -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; -} - -/*! - * @brief This function copies the value in member position - * @param _position New value to be copied in member position - */ -void geometry_msgs::msg::Pose::position( - const geometry_msgs::msg::Point& _position) -{ - m_position = _position; -} - -/*! - * @brief This function moves the value in member position - * @param _position New value to be moved in member position - */ -void geometry_msgs::msg::Pose::position( - geometry_msgs::msg::Point&& _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::Point& geometry_msgs::msg::Pose::position() const -{ - return m_position; -} - -/*! - * @brief This function returns a reference to member position - * @return Reference to member position - */ -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 - */ -void geometry_msgs::msg::Pose::orientation( - const geometry_msgs::msg::Quaternion& _orientation) -{ - m_orientation = _orientation; -} - -/*! - * @brief This function moves the value in member orientation - * @param _orientation New value to be moved in member orientation - */ -void geometry_msgs::msg::Pose::orientation( - geometry_msgs::msg::Quaternion&& _orientation) -{ - m_orientation = std::move(_orientation); -} - -/*! - * @brief This function returns a constant reference to member orientation - * @return Constant reference to member orientation - */ -const geometry_msgs::msg::Quaternion& geometry_msgs::msg::Pose::orientation() const -{ - return m_orientation; -} - -/*! - * @brief This function returns a reference to member orientation - * @return Reference to member orientation - */ -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; -} - -bool geometry_msgs::msg::Pose::isKeyDefined() -{ - return false; -} - -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/types/Pose.h deleted file mode 100644 index 87060b15e47..00000000000 --- a/LibCarla/source/carla/ros2/types/Pose.h +++ /dev/null @@ -1,241 +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 Pose.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_POSE_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_H_ - -#include "Point.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(Pose_SOURCE) -#define Pose_DllAPI __declspec( dllexport ) -#else -#define Pose_DllAPI __declspec( dllimport ) -#endif // Pose_SOURCE -#else -#define Pose_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define Pose_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - -namespace geometry_msgs { - namespace msg { - /*! - * @brief This class represents the structure Pose defined by the user in the IDL file. - * @ingroup POSE - */ - class Pose - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Pose(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Pose(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object geometry_msgs::msg::Pose that will be copied. - */ - eProsima_user_DllExport Pose( - const Pose& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object geometry_msgs::msg::Pose that will be copied. - */ - eProsima_user_DllExport Pose( - Pose&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object geometry_msgs::msg::Pose that will be copied. - */ - eProsima_user_DllExport Pose& operator =( - const Pose& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object geometry_msgs::msg::Pose that will be copied. - */ - eProsima_user_DllExport Pose& operator =( - Pose&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Pose object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Pose& x) const; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Pose object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Pose& x) const; - - /*! - * @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::Point& _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::Point&& _position); - - /*! - * @brief This function returns a constant reference to member position - * @return Constant reference to member position - */ - eProsima_user_DllExport const geometry_msgs::msg::Point& position() const; - - /*! - * @brief This function returns a reference to member position - * @return Reference to member position - */ - eProsima_user_DllExport geometry_msgs::msg::Point& position(); - /*! - * @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 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::Pose& 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::Point m_position; - geometry_msgs::msg::Quaternion m_orientation; - }; - } // namespace msg -} // namespace geometry_msgs - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSE_H_ diff --git a/LibCarla/source/carla/ros2/types/PosePubSubTypes.cpp b/LibCarla/source/carla/ros2/types/PosePubSubTypes.cpp deleted file mode 100644 index a4587eb82c4..00000000000 --- a/LibCarla/source/carla/ros2/types/PosePubSubTypes.cpp +++ /dev/null @@ -1,172 +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.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "PosePubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace geometry_msgs { - namespace msg { - PosePubSubType::PosePubSubType() - { - setName("geometry_msgs::msg::dds_::Pose_"); - auto type_size = Pose::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Pose::isKeyDefined(); - size_t keyLength = Pose::getKeyMaxCdrSerializedSize() > 16 ? - Pose::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - PosePubSubType::~PosePubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool PosePubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Pose* 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 PosePubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //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 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; - } - - std::function PosePubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* PosePubSubType::createData() - { - return reinterpret_cast(new Pose()); - } - - void PosePubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool PosePubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Pose* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Pose::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Pose::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/PosePubSubTypes.h b/LibCarla/source/carla/ros2/types/PosePubSubTypes.h deleted file mode 100644 index 473b30eac8f..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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*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/PoseWithCovariance.cpp b/LibCarla/source/carla/ros2/types/PoseWithCovariance.cpp deleted file mode 100644 index 83e52a52539..00000000000 --- a/LibCarla/source/carla/ros2/types/PoseWithCovariance.cpp +++ /dev/null @@ -1,226 +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 PoseWithCovariance.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 "PoseWithCovariance.h" -#include - -#include -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 - - // geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36 m_covariance - memset(&m_covariance, 0, (36) * 8); -} - -geometry_msgs::msg::PoseWithCovariance::~PoseWithCovariance() -{ -} - -geometry_msgs::msg::PoseWithCovariance::PoseWithCovariance( - const PoseWithCovariance& x) -{ - m_pose = x.m_pose; - m_covariance = x.m_covariance; -} - -geometry_msgs::msg::PoseWithCovariance::PoseWithCovariance( - PoseWithCovariance&& x) noexcept -{ - m_pose = std::move(x.m_pose); - m_covariance = std::move(x.m_covariance); -} - -geometry_msgs::msg::PoseWithCovariance& geometry_msgs::msg::PoseWithCovariance::operator =( - const PoseWithCovariance& x) -{ - m_pose = x.m_pose; - m_covariance = x.m_covariance; - - return *this; -} - -geometry_msgs::msg::PoseWithCovariance& geometry_msgs::msg::PoseWithCovariance::operator =( - PoseWithCovariance&& x) noexcept -{ - m_pose = std::move(x.m_pose); - m_covariance = std::move(x.m_covariance); - - return *this; -} - -bool geometry_msgs::msg::PoseWithCovariance::operator ==( - const PoseWithCovariance& x) const -{ - return (m_pose == x.m_pose && m_covariance == x.m_covariance); -} - -bool geometry_msgs::msg::PoseWithCovariance::operator !=( - const PoseWithCovariance& x) const -{ - return !(*this == x); -} - -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 geometry_msgs::msg::PoseWithCovariance::getCdrSerializedSize( - const geometry_msgs::msg::PoseWithCovariance& data, - size_t current_alignment) -{ - 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); - - return current_alignment - initial_alignment; -} - -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; -} - -/*! - * @brief This function copies the value in member pose - * @param _pose New value to be copied in member pose - */ -void geometry_msgs::msg::PoseWithCovariance::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 geometry_msgs::msg::PoseWithCovariance::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& geometry_msgs::msg::PoseWithCovariance::pose() const -{ - return m_pose; -} - -/*! - * @brief This function returns a reference to member pose - * @return Reference to member pose - */ -geometry_msgs::msg::Pose& geometry_msgs::msg::PoseWithCovariance::pose() -{ - return m_pose; -} -/*! - * @brief This function copies the value in member covariance - * @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) -{ - 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::PoseWithCovariance::covariance( - geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_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::geometry_msgs__PoseWithCovariance__double_array_36& geometry_msgs::msg::PoseWithCovariance::covariance() const -{ - return m_covariance; -} - -/*! - * @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() -{ - 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; -} - -bool geometry_msgs::msg::PoseWithCovariance::isKeyDefined() -{ - return false; -} - -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/types/PoseWithCovariance.h deleted file mode 100644 index 25b061ded4f..00000000000 --- a/LibCarla/source/carla/ros2/types/PoseWithCovariance.h +++ /dev/null @@ -1,242 +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 PoseWithCovariance.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_POSEWITHCOVARIANCE_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_H_ - -#include "Pose.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(PoseWithCovariance_SOURCE) -#define PoseWithCovariance_DllAPI __declspec( dllexport ) -#else -#define PoseWithCovariance_DllAPI __declspec( dllimport ) -#endif // PoseWithCovariance_SOURCE -#else -#define PoseWithCovariance_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define PoseWithCovariance_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - - -namespace geometry_msgs { - namespace msg { - typedef std::array geometry_msgs__PoseWithCovariance__double_array_36; - /*! - * @brief This class represents the structure PoseWithCovariance defined by the user in the IDL file. - * @ingroup POSEWITHCOVARIANCE - */ - class PoseWithCovariance - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport PoseWithCovariance(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~PoseWithCovariance(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object geometry_msgs::msg::PoseWithCovariance that will be copied. - */ - eProsima_user_DllExport PoseWithCovariance( - const PoseWithCovariance& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object geometry_msgs::msg::PoseWithCovariance that will be copied. - */ - eProsima_user_DllExport PoseWithCovariance( - PoseWithCovariance&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object geometry_msgs::msg::PoseWithCovariance that will be copied. - */ - eProsima_user_DllExport PoseWithCovariance& operator =( - const PoseWithCovariance& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object geometry_msgs::msg::PoseWithCovariance that will be copied. - */ - eProsima_user_DllExport PoseWithCovariance& operator =( - PoseWithCovariance&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::PoseWithCovariance object to compare. - */ - eProsima_user_DllExport bool operator ==( - const PoseWithCovariance& x) const; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::PoseWithCovariance object to compare. - */ - eProsima_user_DllExport bool operator !=( - const PoseWithCovariance& x) const; - - /*! - * @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 covariance - * @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); - - /*! - * @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); - - /*! - * @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; - - /*! - * @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(); - - /*! - * @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::PoseWithCovariance& 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::Pose m_pose; - geometry_msgs::msg::geometry_msgs__PoseWithCovariance__double_array_36 m_covariance; - }; - } // namespace msg -} // namespace geometry_msgs - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_POSEWITHCOVARIANCE_H_ diff --git a/LibCarla/source/carla/ros2/types/PoseWithCovariancePubSubTypes.cpp b/LibCarla/source/carla/ros2/types/PoseWithCovariancePubSubTypes.cpp deleted file mode 100644 index fe7a781d6a0..00000000000 --- a/LibCarla/source/carla/ros2/types/PoseWithCovariancePubSubTypes.cpp +++ /dev/null @@ -1,173 +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.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "PoseWithCovariancePubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace geometry_msgs { - namespace msg { - - PoseWithCovariancePubSubType::PoseWithCovariancePubSubType() - { - setName("geometry_msgs::msg::dds_::PoseWithCovariance_"); - auto type_size = PoseWithCovariance::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = PoseWithCovariance::isKeyDefined(); - size_t keyLength = PoseWithCovariance::getKeyMaxCdrSerializedSize() > 16 ? - PoseWithCovariance::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - PoseWithCovariancePubSubType::~PoseWithCovariancePubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool PoseWithCovariancePubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - PoseWithCovariance* 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 PoseWithCovariancePubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //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 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; - } - - std::function PoseWithCovariancePubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* PoseWithCovariancePubSubType::createData() - { - return reinterpret_cast(new PoseWithCovariance()); - } - - void PoseWithCovariancePubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool PoseWithCovariancePubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - PoseWithCovariance* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - PoseWithCovariance::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || PoseWithCovariance::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/PoseWithCovariancePubSubTypes.h b/LibCarla/source/carla/ros2/types/PoseWithCovariancePubSubTypes.h deleted file mode 100644 index c67c05896a3..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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*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..13b9d665c3d --- /dev/null +++ b/LibCarla/source/carla/ros2/types/PublisherSensorType.h @@ -0,0 +1,91 @@ +// 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 + +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, + HSSLidar, + 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"; + case carla::ros2::types::PublisherSensorType::HSSLidar: + return "HSSLidar"; + default: + return "Unknown"; + } +} +} // namespace std diff --git a/LibCarla/source/carla/ros2/types/Quaternion.cpp b/LibCarla/source/carla/ros2/types/Quaternion.cpp deleted file mode 100644 index 4858a84b251..00000000000 --- a/LibCarla/source/carla/ros2/types/Quaternion.cpp +++ /dev/null @@ -1,275 +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 Quaternion.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 "Quaternion.h" -#include - -#include -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 = 0.0; - // double m_y - m_y = 0.0; - // double m_z - m_z = 0.0; - // double m_w - m_w = 1.0; -} - -geometry_msgs::msg::Quaternion::~Quaternion() -{ -} - -geometry_msgs::msg::Quaternion::Quaternion( - const Quaternion& x) -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; - m_w = x.m_w; -} - -geometry_msgs::msg::Quaternion::Quaternion( - Quaternion&& x) noexcept -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; - m_w = x.m_w; -} - -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; - m_w = x.m_w; - - return *this; -} - -geometry_msgs::msg::Quaternion& geometry_msgs::msg::Quaternion::operator =( - Quaternion&& x) noexcept -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; - m_w = x.m_w; - - return *this; -} - -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); -} - -bool geometry_msgs::msg::Quaternion::operator !=( - const Quaternion& x) const -{ - return !(*this == x); -} - -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 geometry_msgs::msg::Quaternion::getCdrSerializedSize( - const geometry_msgs::msg::Quaternion& data, - size_t current_alignment) -{ - (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; - dcdr >> m_w; -} - -/*! - * @brief This function sets a value in member x - * @param _x New value for member x - */ -void geometry_msgs::msg::Quaternion::x( - double _x) -{ - m_x = _x; -} - -/*! - * @brief This function returns the value of member x - * @return Value of member x - */ -double geometry_msgs::msg::Quaternion::x() const -{ - return m_x; -} - -/*! - * @brief This function returns a reference to member x - * @return Reference to member x - */ -double& geometry_msgs::msg::Quaternion::x() -{ - return m_x; -} - -/*! - * @brief This function sets a value in member y - * @param _y New value for member y - */ -void geometry_msgs::msg::Quaternion::y( - double _y) -{ - m_y = _y; -} - -/*! - * @brief This function returns the value of member y - * @return Value of member y - */ -double geometry_msgs::msg::Quaternion::y() const -{ - return m_y; -} - -/*! - * @brief This function returns a reference to member y - * @return Reference to member y - */ -double& geometry_msgs::msg::Quaternion::y() -{ - return m_y; -} - -/*! - * @brief This function sets a value in member z - * @param _z New value for member z - */ -void geometry_msgs::msg::Quaternion::z( - double _z) -{ - m_z = _z; -} - -/*! - * @brief This function returns the value of member z - * @return Value of member z - */ -double geometry_msgs::msg::Quaternion::z() const -{ - return m_z; -} - -/*! - * @brief This function returns a reference to member z - * @return Reference to member z - */ -double& geometry_msgs::msg::Quaternion::z() -{ - return m_z; -} - -/*! - * @brief This function sets a value in member w - * @param _w New value for member w - */ -void geometry_msgs::msg::Quaternion::w( - double _w) -{ - m_w = _w; -} - -/*! - * @brief This function returns the value of member w - * @return Value of member w - */ -double geometry_msgs::msg::Quaternion::w() const -{ - return m_w; -} - -/*! - * @brief This function returns a reference to member w - * @return Reference to member w - */ -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; -} - -bool geometry_msgs::msg::Quaternion::isKeyDefined() -{ - return false; -} - -void geometry_msgs::msg::Quaternion::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/Quaternion.h b/LibCarla/source/carla/ros2/types/Quaternion.h index 5e832eff1bd..432e16ca2f9 100644 --- a/LibCarla/source/carla/ros2/types/Quaternion.h +++ b/LibCarla/source/carla/ros2/types/Quaternion.h @@ -1,265 +1,68 @@ -// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima). -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES 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) 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/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). +*/ +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/QuaternionPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/QuaternionPubSubTypes.cpp deleted file mode 100644 index 8b4581a39a8..00000000000 --- a/LibCarla/source/carla/ros2/types/QuaternionPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 QuaternionPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "QuaternionPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace geometry_msgs { - namespace msg { - QuaternionPubSubType::QuaternionPubSubType() - { - setName("geometry_msgs::msg::dds_::Quaternion_"); - auto type_size = Quaternion::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Quaternion::isKeyDefined(); - size_t keyLength = Quaternion::getKeyMaxCdrSerializedSize() > 16 ? - Quaternion::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - QuaternionPubSubType::~QuaternionPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool QuaternionPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Quaternion* 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 QuaternionPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //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 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; - } - - std::function QuaternionPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* QuaternionPubSubType::createData() - { - return reinterpret_cast(new Quaternion()); - } - - void QuaternionPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool QuaternionPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Quaternion* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Quaternion::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Quaternion::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/QuaternionPubSubTypes.h b/LibCarla/source/carla/ros2/types/QuaternionPubSubTypes.h deleted file mode 100644 index 4dec804a15c..00000000000 --- a/LibCarla/source/carla/ros2/types/QuaternionPubSubTypes.h +++ /dev/null @@ -1,140 +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 QuaternionPubSubTypes.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_QUATERNION_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_PUBSUBTYPES_H_ - -#include -#include - -#include "Quaternion.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated Quaternion 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 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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type Quaternion defined by the user in the IDL file. - * @ingroup QUATERNION - */ - class QuaternionPubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef Quaternion type; - - eProsima_user_DllExport QuaternionPubSubType(); - - eProsima_user_DllExport virtual ~QuaternionPubSubType() 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) Quaternion(); - 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 32ULL == (detail::Quaternion_offset_of() + sizeof(double)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_QUATERNION_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/RegionOfInterest.cpp b/LibCarla/source/carla/ros2/types/RegionOfInterest.cpp deleted file mode 100644 index cf97090b2bc..00000000000 --- a/LibCarla/source/carla/ros2/types/RegionOfInterest.cpp +++ /dev/null @@ -1,312 +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.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 "RegionOfInterest.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define sensor_msgs_msg_RegionOfInterest_max_cdr_typesize 17ULL; -#define sensor_msgs_msg_RegionOfInterest_max_key_cdr_typesize 0ULL; - -sensor_msgs::msg::RegionOfInterest::RegionOfInterest() -{ - // unsigned long m_x_offset - m_x_offset = 0; - // unsigned long m_y_offset - m_y_offset = 0; - // unsigned long m_height - m_height = 0; - // unsigned long m_width - m_width = 0; - // boolean m_do_rectify - m_do_rectify = false; -} - -sensor_msgs::msg::RegionOfInterest::~RegionOfInterest() -{ -} - -sensor_msgs::msg::RegionOfInterest::RegionOfInterest( - const RegionOfInterest& x) -{ - m_x_offset = x.m_x_offset; - m_y_offset = x.m_y_offset; - m_height = x.m_height; - m_width = x.m_width; - m_do_rectify = x.m_do_rectify; -} - -sensor_msgs::msg::RegionOfInterest::RegionOfInterest( - RegionOfInterest&& x) noexcept -{ - m_x_offset = x.m_x_offset; - m_y_offset = x.m_y_offset; - m_height = x.m_height; - m_width = x.m_width; - m_do_rectify = x.m_do_rectify; -} - -sensor_msgs::msg::RegionOfInterest& sensor_msgs::msg::RegionOfInterest::operator =( - const RegionOfInterest& x) -{ - m_x_offset = x.m_x_offset; - m_y_offset = x.m_y_offset; - m_height = x.m_height; - m_width = x.m_width; - m_do_rectify = x.m_do_rectify; - - return *this; -} - -sensor_msgs::msg::RegionOfInterest& sensor_msgs::msg::RegionOfInterest::operator =( - RegionOfInterest&& x) noexcept -{ - m_x_offset = x.m_x_offset; - m_y_offset = x.m_y_offset; - m_height = x.m_height; - m_width = x.m_width; - m_do_rectify = x.m_do_rectify; - - return *this; -} - -bool sensor_msgs::msg::RegionOfInterest::operator ==( - const RegionOfInterest& x) const -{ - return (m_x_offset == x.m_x_offset && m_y_offset == x.m_y_offset && m_height == x.m_height && m_width == x.m_width && m_do_rectify == x.m_do_rectify); -} - -bool sensor_msgs::msg::RegionOfInterest::operator !=( - const RegionOfInterest& x) const -{ - return !(*this == x); -} - -size_t sensor_msgs::msg::RegionOfInterest::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_RegionOfInterest_max_cdr_typesize; -} - -size_t sensor_msgs::msg::RegionOfInterest::getCdrSerializedSize( - const sensor_msgs::msg::RegionOfInterest& 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 += 1 + eprosima::fastcdr::Cdr::alignment(current_alignment, 1); - - return current_alignment - initial_alignment; -} - -void sensor_msgs::msg::RegionOfInterest::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_x_offset; - scdr << m_y_offset; - scdr << m_height; - scdr << m_width; - scdr << m_do_rectify; -} - -void sensor_msgs::msg::RegionOfInterest::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_x_offset; - dcdr >> m_y_offset; - dcdr >> m_height; - dcdr >> m_width; - dcdr >> m_do_rectify; -} - -/*! - * @brief This function sets a value in member x_offset - * @param _x_offset New value for member x_offset - */ -void sensor_msgs::msg::RegionOfInterest::x_offset( - uint32_t _x_offset) -{ - m_x_offset = _x_offset; -} - -/*! - * @brief This function returns the value of member x_offset - * @return Value of member x_offset - */ -uint32_t sensor_msgs::msg::RegionOfInterest::x_offset() const -{ - return m_x_offset; -} - -/*! - * @brief This function returns a reference to member x_offset - * @return Reference to member x_offset - */ -uint32_t& sensor_msgs::msg::RegionOfInterest::x_offset() -{ - return m_x_offset; -} - -/*! - * @brief This function sets a value in member y_offset - * @param _y_offset New value for member y_offset - */ -void sensor_msgs::msg::RegionOfInterest::y_offset( - uint32_t _y_offset) -{ - m_y_offset = _y_offset; -} - -/*! - * @brief This function returns the value of member y_offset - * @return Value of member y_offset - */ -uint32_t sensor_msgs::msg::RegionOfInterest::y_offset() const -{ - return m_y_offset; -} - -/*! - * @brief This function returns a reference to member y_offset - * @return Reference to member y_offset - */ -uint32_t& sensor_msgs::msg::RegionOfInterest::y_offset() -{ - return m_y_offset; -} - -/*! - * @brief This function sets a value in member height - * @param _height New value for member height - */ -void sensor_msgs::msg::RegionOfInterest::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::RegionOfInterest::height() const -{ - return m_height; -} - -/*! - * @brief This function returns a reference to member height - * @return Reference to member height - */ -uint32_t& sensor_msgs::msg::RegionOfInterest::height() -{ - return m_height; -} - -/*! - * @brief This function sets a value in member width - * @param _width New value for member width - */ -void sensor_msgs::msg::RegionOfInterest::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::RegionOfInterest::width() const -{ - return m_width; -} - -/*! - * @brief This function returns a reference to member width - * @return Reference to member width - */ -uint32_t& sensor_msgs::msg::RegionOfInterest::width() -{ - return m_width; -} - -/*! - * @brief This function sets a value in member do_rectify - * @param _do_rectify New value for member do_rectify - */ -void sensor_msgs::msg::RegionOfInterest::do_rectify( - bool _do_rectify) -{ - m_do_rectify = _do_rectify; -} - -/*! - * @brief This function returns the value of member do_rectify - * @return Value of member do_rectify - */ -bool sensor_msgs::msg::RegionOfInterest::do_rectify() const -{ - return m_do_rectify; -} - -/*! - * @brief This function returns a reference to member do_rectify - * @return Reference to member do_rectify - */ -bool& sensor_msgs::msg::RegionOfInterest::do_rectify() -{ - return m_do_rectify; -} - -size_t sensor_msgs::msg::RegionOfInterest::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return sensor_msgs_msg_RegionOfInterest_max_key_cdr_typesize; -} - -bool sensor_msgs::msg::RegionOfInterest::isKeyDefined() -{ - return false; -} - -void sensor_msgs::msg::RegionOfInterest::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} 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.cpp b/LibCarla/source/carla/ros2/types/RegionOfInterestPubSubTypes.cpp deleted file mode 100644 index f622836c032..00000000000 --- a/LibCarla/source/carla/ros2/types/RegionOfInterestPubSubTypes.cpp +++ /dev/null @@ -1,172 +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.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "RegionOfInterestPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace sensor_msgs { - namespace msg { - RegionOfInterestPubSubType::RegionOfInterestPubSubType() - { - setName("sensor_msgs::msg::dds_::RegionOfInterest_"); - auto type_size = RegionOfInterest::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = RegionOfInterest::isKeyDefined(); - size_t keyLength = RegionOfInterest::getKeyMaxCdrSerializedSize() > 16 ? - RegionOfInterest::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - RegionOfInterestPubSubType::~RegionOfInterestPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool RegionOfInterestPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - RegionOfInterest* 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; - - try - { - // Serialize encapsulation - ser.serialize_encapsulation(); - // Serialize the object. - p_type->serialize(ser); - } - catch (eprosima::fastcdr::exception::Exception& /*exception*/) - { - return false; - } - - // Get the serialized length - payload->length = static_cast(ser.getSerializedDataLength()); - return true; - } - - bool RegionOfInterestPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - // Convert DATA to pointer of your type - RegionOfInterest* 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::Exception& /*exception*/) - { - return false; - } - - return true; - } - - std::function RegionOfInterestPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* RegionOfInterestPubSubType::createData() - { - return reinterpret_cast(new RegionOfInterest()); - } - - void RegionOfInterestPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool RegionOfInterestPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - RegionOfInterest* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - RegionOfInterest::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || RegionOfInterest::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/types/RegionOfInterestPubSubTypes.h b/LibCarla/source/carla/ros2/types/RegionOfInterestPubSubTypes.h deleted file mode 100644 index ecbdfe980f2..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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*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..709b8e88821 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/SensorActorDefinition.h @@ -0,0 +1,42 @@ +// 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/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/String.cpp b/LibCarla/source/carla/ros2/types/String.cpp deleted file mode 100644 index 50afa10b420..00000000000 --- a/LibCarla/source/carla/ros2/types/String.cpp +++ /dev/null @@ -1,173 +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 String.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 "String.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define std_msgs_msg_String_max_cdr_typesize 260ULL; -#define std_msgs_msg_String_max_key_cdr_typesize 0ULL; - -std_msgs::msg::String::String() -{ - // string m_data - m_data =""; -} - -std_msgs::msg::String::~String() -{ -} - -std_msgs::msg::String::String( - const String& x) -{ - m_data = x.m_data; -} - -std_msgs::msg::String::String( - String&& x) noexcept -{ - m_data = std::move(x.m_data); -} - -std_msgs::msg::String& std_msgs::msg::String::operator =( - const String& x) -{ - m_data = x.m_data; - - return *this; -} - -std_msgs::msg::String& std_msgs::msg::String::operator =( - String&& x) noexcept -{ - m_data = std::move(x.m_data); - - return *this; -} - -bool std_msgs::msg::String::operator ==( - const String& x) const -{ - return (m_data == x.m_data); -} - -bool std_msgs::msg::String::operator !=( - const String& x) const -{ - return !(*this == x); -} - -size_t std_msgs::msg::String::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return std_msgs_msg_String_max_cdr_typesize; -} - -size_t std_msgs::msg::String::getCdrSerializedSize( - const std_msgs::msg::String& data, - size_t current_alignment) -{ - size_t initial_alignment = current_alignment; - current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.data().size() + 1; - - return current_alignment - initial_alignment; -} - -void std_msgs::msg::String::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_data.c_str(); -} - -void std_msgs::msg::String::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 std_msgs::msg::String::data( - const std::string& _data) -{ - m_data = _data; -} - -/*! - * @brief This function moves the value in member data - * @param _data New value to be moved in member data - */ -void std_msgs::msg::String::data( - std::string&& _data) -{ - m_data = std::move(_data); -} - -/*! - * @brief This function returns a constant reference to member data - * @return Constant reference to member data - */ -const std::string& std_msgs::msg::String::data() const -{ - return m_data; -} - -/*! - * @brief This function returns a reference to member data - * @return Reference to member data - */ -std::string& std_msgs::msg::String::data() -{ - return m_data; -} - -size_t std_msgs::msg::String::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return std_msgs_msg_String_max_key_cdr_typesize; -} - -bool std_msgs::msg::String::isKeyDefined() -{ - return false; -} - -void std_msgs::msg::String::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/String.h b/LibCarla/source/carla/ros2/types/String.h deleted file mode 100644 index 1c99d0d8a2d..00000000000 --- a/LibCarla/source/carla/ros2/types/String.h +++ /dev/null @@ -1,212 +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 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/types/StringPubSubTypes.cpp deleted file mode 100644 index 241514542d8..00000000000 --- a/LibCarla/source/carla/ros2/types/StringPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 StringPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "StringPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace std_msgs { - namespace msg { - StringPubSubType::StringPubSubType() - { - setName("std_msgs::msg::dds_::String_"); - auto type_size = String::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = String::isKeyDefined(); - size_t keyLength = String::getKeyMaxCdrSerializedSize() > 16 ? - String::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - StringPubSubType::~StringPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool StringPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - String* 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 StringPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - String* 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; - } - - std::function StringPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* StringPubSubType::createData() - { - return reinterpret_cast(new String()); - } - - void StringPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool StringPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - String* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - String::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || String::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 std_msgs diff --git a/LibCarla/source/carla/ros2/types/StringPubSubTypes.h b/LibCarla/source/carla/ros2/types/StringPubSubTypes.h deleted file mode 100644 index 749abb654c6..00000000000 --- a/LibCarla/source/carla/ros2/types/StringPubSubTypes.h +++ /dev/null @@ -1,106 +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 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; - }; - } -} - -#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/types/TF2Error.cpp deleted file mode 100644 index 63f3ad11c5a..00000000000 --- a/LibCarla/source/carla/ros2/types/TF2Error.cpp +++ /dev/null @@ -1,211 +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 TF2Error.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 "TF2Error.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define tf2_msgs_msg_TF2Error_max_cdr_typesize 264ULL; -#define tf2_msgs_msg_TF2Error_max_key_cdr_typesize 0ULL; - -tf2_msgs::msg::TF2Error::TF2Error() -{ - // octet m_error - m_error = 0; - // string m_error_string - m_error_string =""; -} - -tf2_msgs::msg::TF2Error::~TF2Error() -{ -} - -tf2_msgs::msg::TF2Error::TF2Error( - const TF2Error& x) -{ - m_error = x.m_error; - m_error_string = x.m_error_string; -} - -tf2_msgs::msg::TF2Error::TF2Error( - TF2Error&& x) noexcept -{ - m_error = x.m_error; - m_error_string = std::move(x.m_error_string); -} - -tf2_msgs::msg::TF2Error& tf2_msgs::msg::TF2Error::operator =( - const TF2Error& x) -{ - m_error = x.m_error; - m_error_string = x.m_error_string; - - return *this; -} - -tf2_msgs::msg::TF2Error& tf2_msgs::msg::TF2Error::operator =( - TF2Error&& x) noexcept -{ - m_error = x.m_error; - m_error_string = std::move(x.m_error_string); - - return *this; -} - -bool tf2_msgs::msg::TF2Error::operator ==( - const TF2Error& x) const -{ - return (m_error == x.m_error && m_error_string == x.m_error_string); -} - -bool tf2_msgs::msg::TF2Error::operator !=( - const TF2Error& x) const -{ - return !(*this == x); -} - -size_t tf2_msgs::msg::TF2Error::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return tf2_msgs_msg_TF2Error_max_cdr_typesize; -} - -size_t tf2_msgs::msg::TF2Error::getCdrSerializedSize( - const tf2_msgs::msg::TF2Error& data, - 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) + data.error_string().size() + 1; - - return current_alignment - initial_alignment; -} - -void tf2_msgs::msg::TF2Error::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_error; - scdr << m_error_string.c_str(); -} - -void tf2_msgs::msg::TF2Error::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_error; - dcdr >> m_error_string; -} - -/*! - * @brief This function sets a value in member error - * @param _error New value for member error - */ -void tf2_msgs::msg::TF2Error::error( - uint8_t _error) -{ - m_error = _error; -} - -/*! - * @brief This function returns the value of member error - * @return Value of member error - */ -uint8_t tf2_msgs::msg::TF2Error::error() const -{ - return m_error; -} - -/*! - * @brief This function returns a reference to member error - * @return Reference to member error - */ -uint8_t& tf2_msgs::msg::TF2Error::error() -{ - return m_error; -} - -/*! - * @brief This function copies the value in member error_string - * @param _error_string New value to be copied in member error_string - */ -void tf2_msgs::msg::TF2Error::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 tf2_msgs::msg::TF2Error::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& tf2_msgs::msg::TF2Error::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& tf2_msgs::msg::TF2Error::error_string() -{ - return m_error_string; -} - - -size_t tf2_msgs::msg::TF2Error::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return tf2_msgs_msg_TF2Error_max_key_cdr_typesize; -} - -bool tf2_msgs::msg::TF2Error::isKeyDefined() -{ - return false; -} - -void tf2_msgs::msg::TF2Error::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/TF2Error.h b/LibCarla/source/carla/ros2/types/TF2Error.h deleted file mode 100644 index 07b5804d4db..00000000000 --- a/LibCarla/source/carla/ros2/types/TF2Error.h +++ /dev/null @@ -1,240 +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 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/types/TF2ErrorPubSubTypes.cpp deleted file mode 100644 index d49b2c534ee..00000000000 --- a/LibCarla/source/carla/ros2/types/TF2ErrorPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 TF2ErrorPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "TF2ErrorPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace tf2_msgs { - namespace msg { - TF2ErrorPubSubType::TF2ErrorPubSubType() - { - setName("tf2_msgs::msg::dds_::TF2Error_"); - auto type_size = TF2Error::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = TF2Error::isKeyDefined(); - size_t keyLength = TF2Error::getKeyMaxCdrSerializedSize() > 16 ? - TF2Error::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - TF2ErrorPubSubType::~TF2ErrorPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool TF2ErrorPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - TF2Error* 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 TF2ErrorPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - TF2Error* 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; - } - - std::function TF2ErrorPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* TF2ErrorPubSubType::createData() - { - return reinterpret_cast(new TF2Error()); - } - - void TF2ErrorPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool TF2ErrorPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - TF2Error* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - TF2Error::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || TF2Error::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 tf2_msgs diff --git a/LibCarla/source/carla/ros2/types/TF2ErrorPubSubTypes.h b/LibCarla/source/carla/ros2/types/TF2ErrorPubSubTypes.h deleted file mode 100644 index c160a65e4d5..00000000000 --- a/LibCarla/source/carla/ros2/types/TF2ErrorPubSubTypes.h +++ /dev/null @@ -1,105 +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 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; - }; - } -} - -#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/types/TFMessage.cpp deleted file mode 100644 index 86824a99acf..00000000000 --- a/LibCarla/source/carla/ros2/types/TFMessage.cpp +++ /dev/null @@ -1,188 +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 TFMessage.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 "TFMessage.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define geometry_msgs_msg_Vector3_max_cdr_typesize 24ULL; -#define geometry_msgs_msg_Transform_max_cdr_typesize 56ULL; -#define tf2_msgs_msg_TFMessage_max_cdr_typesize 58408ULL; -#define std_msgs_msg_Time_max_cdr_typesize 8ULL; -#define geometry_msgs_msg_TransformStamped_max_cdr_typesize 584ULL; -#define geometry_msgs_msg_Quaternion_max_cdr_typesize 32ULL; -#define std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Transform_max_key_cdr_typesize 0ULL; -#define tf2_msgs_msg_TFMessage_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Time_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_TransformStamped_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Quaternion_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; - -tf2_msgs::msg::TFMessage::TFMessage() -{ -} - -tf2_msgs::msg::TFMessage::~TFMessage() -{ -} - -tf2_msgs::msg::TFMessage::TFMessage( - const TFMessage& x) -{ - m_transforms = x.m_transforms; -} - -tf2_msgs::msg::TFMessage::TFMessage( - TFMessage&& x) noexcept -{ - m_transforms = std::move(x.m_transforms); -} - -tf2_msgs::msg::TFMessage& tf2_msgs::msg::TFMessage::operator =( - const TFMessage& x) -{ - m_transforms = x.m_transforms; - - return *this; -} - -tf2_msgs::msg::TFMessage& tf2_msgs::msg::TFMessage::operator =( - TFMessage&& x) noexcept -{ - m_transforms = std::move(x.m_transforms); - - return *this; -} - -bool tf2_msgs::msg::TFMessage::operator ==( - const TFMessage& x) const -{ - return (m_transforms == x.m_transforms); -} - -bool tf2_msgs::msg::TFMessage::operator !=( - const TFMessage& x) const -{ - return !(*this == x); -} - -size_t tf2_msgs::msg::TFMessage::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return tf2_msgs_msg_TFMessage_max_cdr_typesize; -} - -size_t tf2_msgs::msg::TFMessage::getCdrSerializedSize( - const tf2_msgs::msg::TFMessage& data, - 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 < data.transforms().size(); ++a) - { - current_alignment += geometry_msgs::msg::TransformStamped::getCdrSerializedSize(data.transforms().at(a), current_alignment); - } - - return current_alignment - initial_alignment; -} - -void tf2_msgs::msg::TFMessage::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_transforms; -} - -void tf2_msgs::msg::TFMessage::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_transforms; -} - -/*! - * @brief This function copies the value in member transforms - * @param _transforms New value to be copied in member transforms - */ -void tf2_msgs::msg::TFMessage::transforms( - const std::vector& _transforms) -{ - m_transforms = _transforms; -} - -/*! - * @brief This function moves the value in member transforms - * @param _transforms New value to be moved in member transforms - */ -void tf2_msgs::msg::TFMessage::transforms( - std::vector&& _transforms) -{ - m_transforms = std::move(_transforms); -} - -/*! - * @brief This function returns a constant reference to member transforms - * @return Constant reference to member transforms - */ -const std::vector& tf2_msgs::msg::TFMessage::transforms() const -{ - return m_transforms; -} - -/*! - * @brief This function returns a reference to member transforms - * @return Reference to member transforms - */ -std::vector& tf2_msgs::msg::TFMessage::transforms() -{ - return m_transforms; -} - -size_t tf2_msgs::msg::TFMessage::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return tf2_msgs_msg_TFMessage_max_key_cdr_typesize; -} - -bool tf2_msgs::msg::TFMessage::isKeyDefined() -{ - return false; -} - -void tf2_msgs::msg::TFMessage::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/TFMessage.h b/LibCarla/source/carla/ros2/types/TFMessage.h deleted file mode 100644 index adb9e9a7954..00000000000 --- a/LibCarla/source/carla/ros2/types/TFMessage.h +++ /dev/null @@ -1,216 +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 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 "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/types/TFMessagePubSubTypes.cpp deleted file mode 100644 index 526d0356d44..00000000000 --- a/LibCarla/source/carla/ros2/types/TFMessagePubSubTypes.cpp +++ /dev/null @@ -1,172 +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 TFMessagePubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "TFMessagePubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace tf2_msgs { - namespace msg { - TFMessagePubSubType::TFMessagePubSubType() - { - setName("tf2_msgs::msg::dds_::TFMessage_"); - auto type_size = TFMessage::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = TFMessage::isKeyDefined(); - size_t keyLength = TFMessage::getKeyMaxCdrSerializedSize() > 16 ? - TFMessage::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - TFMessagePubSubType::~TFMessagePubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool TFMessagePubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - TFMessage* 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 TFMessagePubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - TFMessage* 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; - } - - std::function TFMessagePubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* TFMessagePubSubType::createData() - { - return reinterpret_cast(new TFMessage()); - } - - void TFMessagePubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool TFMessagePubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - TFMessage* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - TFMessage::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || TFMessage::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 tf2_msgs diff --git a/LibCarla/source/carla/ros2/types/TFMessagePubSubTypes.h b/LibCarla/source/carla/ros2/types/TFMessagePubSubTypes.h deleted file mode 100644 index 5dbd16037bf..00000000000 --- a/LibCarla/source/carla/ros2/types/TFMessagePubSubTypes.h +++ /dev/null @@ -1,108 +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 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 "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; - }; - } -} - -#endif // _FAST_DDS_GENERATED_TF2_MSGS_MSG_TFMESSAGE_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Time.cpp b/LibCarla/source/carla/ros2/types/Time.cpp deleted file mode 100644 index 95f2e7b95ce..00000000000 --- a/LibCarla/source/carla/ros2/types/Time.cpp +++ /dev/null @@ -1,201 +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 Time.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 "Time.h" -#include - -#include -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 = 0; - // unsigned long m_nanosec - m_nanosec = 0; -} - -builtin_interfaces::msg::Time::~Time() -{ -} - -builtin_interfaces::msg::Time::Time( - const Time& x) -{ - m_sec = x.m_sec; - m_nanosec = x.m_nanosec; -} - -builtin_interfaces::msg::Time::Time( - Time&& x) noexcept -{ - m_sec = x.m_sec; - m_nanosec = x.m_nanosec; -} - -builtin_interfaces::msg::Time& builtin_interfaces::msg::Time::operator =( - const Time& x) -{ - m_sec = x.m_sec; - m_nanosec = x.m_nanosec; - - return *this; -} - -builtin_interfaces::msg::Time& builtin_interfaces::msg::Time::operator =( - Time&& x) noexcept -{ - m_sec = x.m_sec; - m_nanosec = x.m_nanosec; - - return *this; -} - -bool builtin_interfaces::msg::Time::operator ==( - const Time& x) const -{ - return (m_sec == x.m_sec && m_nanosec == x.m_nanosec); -} - -bool builtin_interfaces::msg::Time::operator !=( - const Time& x) const -{ - return !(*this == x); -} - -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 builtin_interfaces::msg::Time::getCdrSerializedSize( - const builtin_interfaces::msg::Time& 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); - - 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; -} - -/*! - * @brief This function sets a value in member sec - * @param _sec New value for member sec - */ -void builtin_interfaces::msg::Time::sec( - int32_t _sec) -{ - m_sec = _sec; -} - -/*! - * @brief This function returns the value of member sec - * @return Value of member sec - */ -int32_t builtin_interfaces::msg::Time::sec() const -{ - return m_sec; -} - -/*! - * @brief This function returns a reference to member sec - * @return Reference to member sec - */ -int32_t& builtin_interfaces::msg::Time::sec() -{ - return m_sec; -} - -/*! - * @brief This function sets a value in member nanosec - * @param _nanosec New value for member nanosec - */ -void builtin_interfaces::msg::Time::nanosec( - uint32_t _nanosec) -{ - m_nanosec = _nanosec; -} - -/*! - * @brief This function returns the value of member nanosec - * @return Value of member nanosec - */ -uint32_t builtin_interfaces::msg::Time::nanosec() const -{ - return m_nanosec; -} - -/*! - * @brief This function returns a reference to member nanosec - * @return Reference to member nanosec - */ -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; -} - -bool builtin_interfaces::msg::Time::isKeyDefined() -{ - return false; -} - -void builtin_interfaces::msg::Time::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/Time.h b/LibCarla/source/carla/ros2/types/Time.h deleted file mode 100644 index 216907bfda2..00000000000 --- a/LibCarla/source/carla/ros2/types/Time.h +++ /dev/null @@ -1,226 +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 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 -#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) noexcept; - - /*! - * @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) noexcept; - - /*! - * @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_ diff --git a/LibCarla/source/carla/ros2/types/TimePubSubTypes.cpp b/LibCarla/source/carla/ros2/types/TimePubSubTypes.cpp deleted file mode 100644 index 8bb4969d9ad..00000000000 --- a/LibCarla/source/carla/ros2/types/TimePubSubTypes.cpp +++ /dev/null @@ -1,155 +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 TimePubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "TimePubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace builtin_interfaces { - namespace msg { - TimePubSubType::TimePubSubType() - { - setName("builtin_interfaces::msg::dds_::Time_"); - auto type_size = Time::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Time::isKeyDefined(); - size_t keyLength = Time::getKeyMaxCdrSerializedSize() > 16 ? - Time::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - TimePubSubType::~TimePubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool TimePubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Time* 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; - } - - bool TimePubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - //Convert DATA to pointer of your type - Time* 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; - } - - std::function TimePubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* TimePubSubType::createData() - { - return reinterpret_cast(new Time()); - } - - void TimePubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool TimePubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Time* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Time::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Time::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 builtin_interfaces diff --git a/LibCarla/source/carla/ros2/types/TimePubSubTypes.h b/LibCarla/source/carla/ros2/types/TimePubSubTypes.h deleted file mode 100644 index 9a2a4d9a8c8..00000000000 --- a/LibCarla/source/carla/ros2/types/TimePubSubTypes.h +++ /dev/null @@ -1,105 +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 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() 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 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; - }; - } -} - -#endif // _FAST_DDS_GENERATED_BUILTIN_INTERFACES_MSG_TIME_PUBSUBTYPES_H_ diff --git a/LibCarla/source/carla/ros2/types/Timestamp.h b/LibCarla/source/carla/ros2/types/Timestamp.h new file mode 100644 index 00000000000..ea8ea029202 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/Timestamp.h @@ -0,0 +1,56 @@ +// 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 "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..d5f42941b66 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/TrafficLightActorDefinition.h @@ -0,0 +1,48 @@ +// 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/types/ActorDefinition.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 ActorDefinition { + TrafficLightActorDefinition(ActorNameDefinition const &actor_name_definition, carla::geom::BoundingBox const &bounding_box, carla::geom::BoundingBox const &trigger_volume_in) + : ActorDefinition(actor_name_definition, bounding_box) + , trigger_volume(trigger_volume_in) {} + + carla::geom::BoundingBox trigger_volume; +}; +} // 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..dd11a8a2c52 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/TrafficSignActorDefinition.h @@ -0,0 +1,29 @@ +// 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/types/ActorDefinition.h" + +namespace carla { +namespace ros2 { +namespace types { + +struct TrafficSignActorDefinition : public ActorDefinition { + TrafficSignActorDefinition(ActorNameDefinition const &actor_name_definition, carla::geom::BoundingBox const &bounding_box) + : ActorDefinition(actor_name_definition, bounding_box) {} + 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.cpp b/LibCarla/source/carla/ros2/types/Transform.cpp deleted file mode 100644 index 0d2056533ab..00000000000 --- a/LibCarla/source/carla/ros2/types/Transform.cpp +++ /dev/null @@ -1,219 +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 Transform.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 "Transform.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define geometry_msgs_msg_Vector3_max_cdr_typesize 24ULL; -#define geometry_msgs_msg_Transform_max_cdr_typesize 56ULL; -#define geometry_msgs_msg_Quaternion_max_cdr_typesize 32ULL; -#define geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Transform_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Quaternion_max_key_cdr_typesize 0ULL; - -geometry_msgs::msg::Transform::Transform() -{ -} - -geometry_msgs::msg::Transform::~Transform() -{ -} - -geometry_msgs::msg::Transform::Transform( - const Transform& x) -{ - m_translation = x.m_translation; - m_rotation = x.m_rotation; -} - -geometry_msgs::msg::Transform::Transform( - Transform&& x) noexcept -{ - m_translation = std::move(x.m_translation); - m_rotation = std::move(x.m_rotation); -} - -geometry_msgs::msg::Transform& geometry_msgs::msg::Transform::operator =( - const Transform& x) -{ - m_translation = x.m_translation; - m_rotation = x.m_rotation; - - return *this; -} - -geometry_msgs::msg::Transform& geometry_msgs::msg::Transform::operator =( - Transform&& x) noexcept -{ - m_translation = std::move(x.m_translation); - m_rotation = std::move(x.m_rotation); - - return *this; -} - -bool geometry_msgs::msg::Transform::operator ==( - const Transform& x) const -{ - return (m_translation == x.m_translation && m_rotation == x.m_rotation); -} - -bool geometry_msgs::msg::Transform::operator !=( - const Transform& x) const -{ - return !(*this == x); -} - -size_t geometry_msgs::msg::Transform::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return geometry_msgs_msg_Transform_max_cdr_typesize; -} - -size_t geometry_msgs::msg::Transform::getCdrSerializedSize( - const geometry_msgs::msg::Transform& data, - size_t current_alignment) -{ - size_t initial_alignment = current_alignment; - current_alignment += geometry_msgs::msg::Vector3::getCdrSerializedSize(data.translation(), current_alignment); - current_alignment += geometry_msgs::msg::Quaternion::getCdrSerializedSize(data.rotation(), current_alignment); - - return current_alignment - initial_alignment; -} - -void geometry_msgs::msg::Transform::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_translation; - scdr << m_rotation; -} - -void geometry_msgs::msg::Transform::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_translation; - dcdr >> m_rotation; -} - -/*! - * @brief This function copies the value in member translation - * @param _translation New value to be copied in member translation - */ -void geometry_msgs::msg::Transform::translation( - const geometry_msgs::msg::Vector3& _translation) -{ - m_translation = _translation; -} - -/*! - * @brief This function moves the value in member translation - * @param _translation New value to be moved in member translation - */ -void geometry_msgs::msg::Transform::translation( - geometry_msgs::msg::Vector3&& _translation) -{ - m_translation = std::move(_translation); -} - -/*! - * @brief This function returns a constant reference to member translation - * @return Constant reference to member translation - */ -const geometry_msgs::msg::Vector3& geometry_msgs::msg::Transform::translation() const -{ - return m_translation; -} - -/*! - * @brief This function returns a reference to member translation - * @return Reference to member translation - */ -geometry_msgs::msg::Vector3& geometry_msgs::msg::Transform::translation() -{ - return m_translation; -} -/*! - * @brief This function copies the value in member rotation - * @param _rotation New value to be copied in member rotation - */ -void geometry_msgs::msg::Transform::rotation( - const geometry_msgs::msg::Quaternion& _rotation) -{ - m_rotation = _rotation; -} - -/*! - * @brief This function moves the value in member rotation - * @param _rotation New value to be moved in member rotation - */ -void geometry_msgs::msg::Transform::rotation( - geometry_msgs::msg::Quaternion&& _rotation) -{ - m_rotation = std::move(_rotation); -} - -/*! - * @brief This function returns a constant reference to member rotation - * @return Constant reference to member rotation - */ -const geometry_msgs::msg::Quaternion& geometry_msgs::msg::Transform::rotation() const -{ - return m_rotation; -} - -/*! - * @brief This function returns a reference to member rotation - * @return Reference to member rotation - */ -geometry_msgs::msg::Quaternion& geometry_msgs::msg::Transform::rotation() -{ - return m_rotation; -} - -size_t geometry_msgs::msg::Transform::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return geometry_msgs_msg_Transform_max_key_cdr_typesize; -} - -bool geometry_msgs::msg::Transform::isKeyDefined() -{ - return false; -} - -void geometry_msgs::msg::Transform::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/Transform.h b/LibCarla/source/carla/ros2/types/Transform.h index daca6910321..171cb00300e 100644 --- a/LibCarla/source/carla/ros2/types/Transform.h +++ b/LibCarla/source/carla/ros2/types/Transform.h @@ -1,241 +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 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) 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/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_location(carla_transform.location) + , _carla_rotation(carla_transform.rotation) + , _carla_rotation_initialized(true) + , _carla_quaternion(carla_quaternion) { + init_ros_transform(); + } + + explicit Transform(const carla::geom::Location& carla_location, const carla::geom::Quaternion& carla_quaternion) + : _carla_location(carla_location) + , _carla_rotation_initialized(false) + , _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_location = CoordinateSystemTransform::TransformLinearAxixVector3D(ros_location); + auto const quaternion = carla::ros2::types::Quaternion(_ros_transform.rotation()); + _carla_quaternion = quaternion.GetQuaternion(); + _carla_rotation_initialized = false; + } + +#ifdef LIBCARLA_INCLUDED_FROM_UE4 + Transform(const FTransform& ue4_transform) + : _carla_location(ue4_transform.GetLocation()) + , _carla_rotation(ue4_transform.Rotator()) + , _carla_rotation_initialized(true) + , _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 + */ + 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 + */ + 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 + */ + carla::geom::Transform GetTransform() const { + EnsureCarlaRotatorInitialized(); + return carla::geom::Transform(_carla_location, _carla_rotation); + } + + /** + * The carla Location + * + * Uses CARLA naming convention + */ + const carla::geom::Location& GetLocation() const { + return _carla_location; + } + + /** + * The carla Rotator + * + * Uses CARLA naming convention + */ + const carla::geom::Rotation& GetRotator() const { + EnsureCarlaRotatorInitialized(); + return _carla_rotation; + } + + /** + * The carla Quaternion + * + * Uses CARLA naming convention + */ + const carla::geom::Quaternion& GetQuaternion() const { + return _carla_quaternion; + } + + /** + * Transform the in_point + */ + void TransformPoint(carla::geom::Vector3D &in_point) const { + carla::geom::Vector3D rotated_point = _carla_quaternion.RotatedPoint(in_point); // First rotate + in_point = rotated_point + carla::geom::Vector3D(_carla_location); // Then translate + } + + /** + * Get the transform of this relative to the provided base transform. + */ + carla::ros2::types::Transform GetRelativeTransform(carla::ros2::types::Transform const &basis) const { + auto const relative_quaternion_new_base = basis.GetQuaternion().Inverse() * GetQuaternion(); + auto const relative_location_current_base = GetLocation() - basis.GetLocation(); + carla::geom::Location const relative_location_new_base = carla::geom::Vector3D(basis.GetQuaternion().InverseRotatedPoint(relative_location_current_base)); + carla::ros2::types::Transform relative_transform(relative_location_new_base, relative_quaternion_new_base); + return relative_transform; + } + +private: + void EnsureCarlaRotatorInitialized() const { + if ( !_carla_rotation_initialized ) { + _carla_rotation_initialized = true; + _carla_rotation = _carla_quaternion.Rotator(); + } + } + + void init_ros_transform() { + // switch y-axis from right to left -> negate y-axis + _ros_transform.translation() = CoordinateSystemTransform::TransformLinearAxisMsg(_carla_location); + _ros_transform.rotation(carla::ros2::types::Quaternion(_carla_quaternion).quaternion()); + } + + // keep the carla types, but with rotation optional + // be aware: rotation calculation requires some sin/cos calls and is rather expensive + // therefore, calculate rotation only if actually required (e.g. in case of ROS input) + // make the rotation mutable to allow lazy initialization in const methods + mutable carla::geom::Rotation _carla_rotation; + mutable bool _carla_rotation_initialized = false; + carla::geom::Location _carla_location; + carla::geom::Quaternion _carla_quaternion; + geometry_msgs::msg::Transform _ros_transform; +}; +} // namespace types +} // namespace ros2 +} // namespace carla + + +namespace std { + +inline std::string to_string(geometry_msgs::msg::Transform const &transform) { + return "ROSTransform(translation(x=" + + std::to_string(transform.translation().x()) + ", y=" + + std::to_string(transform.translation().y()) + ", z=" + + std::to_string(transform.translation().z()) + "), " + + "rotation(x=" + + std::to_string(transform.rotation().x()) + ", y=" + + std::to_string(transform.rotation().y()) + ", z=" + + std::to_string(transform.rotation().z()) + ", w=" + + std::to_string(transform.rotation().w()) + "))"; +} + +inline std::string to_string(carla::ros2::types::Transform const &transform) { + return "Transform(" + std::to_string(transform.transform()) + " CARLA: " + + std::to_string(transform.GetQuaternion()) + std::to_string(transform.GetLocation()) + std::to_string(transform.GetRotator()) + ")"; +} + +} // namespace std \ No newline at end of file diff --git a/LibCarla/source/carla/ros2/types/TransformPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/TransformPubSubTypes.cpp deleted file mode 100644 index 6acb6b5ee51..00000000000 --- a/LibCarla/source/carla/ros2/types/TransformPubSubTypes.cpp +++ /dev/null @@ -1,172 +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.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "TransformPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace geometry_msgs { - namespace msg { - TransformPubSubType::TransformPubSubType() - { - setName("geometry_msgs::msg::dds_::Transform_"); - auto type_size = Transform::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Transform::isKeyDefined(); - size_t keyLength = Transform::getKeyMaxCdrSerializedSize() > 16 ? - Transform::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - TransformPubSubType::~TransformPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool TransformPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Transform* 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 TransformPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - Transform* 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; - } - - std::function TransformPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* TransformPubSubType::createData() - { - return reinterpret_cast(new Transform()); - } - - void TransformPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool TransformPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Transform* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Transform::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Transform::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/TransformPubSubTypes.h b/LibCarla/source/carla/ros2/types/TransformPubSubTypes.h deleted file mode 100644 index 39c45268026..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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*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/TransformStamped.cpp b/LibCarla/source/carla/ros2/types/TransformStamped.cpp deleted file mode 100644 index 243d28fbe60..00000000000 --- a/LibCarla/source/carla/ros2/types/TransformStamped.cpp +++ /dev/null @@ -1,276 +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 TransformStamped.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 "TransformStamped.h" -#include - -#include -using namespace eprosima::fastcdr::exception; - -#include - -#define geometry_msgs_msg_Vector3_max_cdr_typesize 24ULL; -#define geometry_msgs_msg_Transform_max_cdr_typesize 56ULL; -#define std_msgs_msg_Time_max_cdr_typesize 8ULL; -#define geometry_msgs_msg_TransformStamped_max_cdr_typesize 584ULL; -#define geometry_msgs_msg_Quaternion_max_cdr_typesize 32ULL; -#define std_msgs_msg_Header_max_cdr_typesize 268ULL; -#define geometry_msgs_msg_Vector3_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Transform_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Time_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_TransformStamped_max_key_cdr_typesize 0ULL; -#define geometry_msgs_msg_Quaternion_max_key_cdr_typesize 0ULL; -#define std_msgs_msg_Header_max_key_cdr_typesize 0ULL; - -geometry_msgs::msg::TransformStamped::TransformStamped() -{ - // std_msgs::msg::Header m_header - - // string m_child_frame_id - m_child_frame_id =""; - // geometry_msgs::msg::Transform m_transform -} - -geometry_msgs::msg::TransformStamped::~TransformStamped() -{ -} - -geometry_msgs::msg::TransformStamped::TransformStamped( - const TransformStamped& x) -{ - m_header = x.m_header; - m_child_frame_id = x.m_child_frame_id; - m_transform = x.m_transform; -} - -geometry_msgs::msg::TransformStamped::TransformStamped( - TransformStamped&& x) noexcept -{ - m_header = std::move(x.m_header); - m_child_frame_id = std::move(x.m_child_frame_id); - m_transform = std::move(x.m_transform); -} - -geometry_msgs::msg::TransformStamped& geometry_msgs::msg::TransformStamped::operator =( - const TransformStamped& x) -{ - m_header = x.m_header; - m_child_frame_id = x.m_child_frame_id; - m_transform = x.m_transform; - - return *this; -} - -geometry_msgs::msg::TransformStamped& geometry_msgs::msg::TransformStamped::operator =( - TransformStamped&& x) noexcept -{ - m_header = std::move(x.m_header); - m_child_frame_id = std::move(x.m_child_frame_id); - m_transform = std::move(x.m_transform); - - return *this; -} - -bool geometry_msgs::msg::TransformStamped::operator ==( - const TransformStamped& x) const -{ - return (m_header == x.m_header && m_child_frame_id == x.m_child_frame_id && m_transform == x.m_transform); -} - -bool geometry_msgs::msg::TransformStamped::operator !=( - const TransformStamped& x) const -{ - return !(*this == x); -} - -size_t geometry_msgs::msg::TransformStamped::getMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return geometry_msgs_msg_TransformStamped_max_cdr_typesize; -} - -size_t geometry_msgs::msg::TransformStamped::getCdrSerializedSize( - const geometry_msgs::msg::TransformStamped& 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) + data.child_frame_id().size() + 1; - current_alignment += geometry_msgs::msg::Transform::getCdrSerializedSize(data.transform(), current_alignment); - - return current_alignment - initial_alignment; -} - -void geometry_msgs::msg::TransformStamped::serialize( - eprosima::fastcdr::Cdr& scdr) const -{ - scdr << m_header; - scdr << m_child_frame_id.c_str(); - scdr << m_transform; -} - -void geometry_msgs::msg::TransformStamped::deserialize( - eprosima::fastcdr::Cdr& dcdr) -{ - dcdr >> m_header; - dcdr >> m_child_frame_id; - dcdr >> m_transform; -} - -/*! - * @brief This function copies the value in member header - * @param _header New value to be copied in member header - */ -void geometry_msgs::msg::TransformStamped::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 geometry_msgs::msg::TransformStamped::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& geometry_msgs::msg::TransformStamped::header() const -{ - return m_header; -} - -/*! - * @brief This function returns a reference to member header - * @return Reference to member header - */ -std_msgs::msg::Header& geometry_msgs::msg::TransformStamped::header() -{ - return m_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 - */ -void geometry_msgs::msg::TransformStamped::child_frame_id( - const std::string& _child_frame_id) -{ - m_child_frame_id = _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 - */ -void geometry_msgs::msg::TransformStamped::child_frame_id( - std::string&& _child_frame_id) -{ - m_child_frame_id = std::move(_child_frame_id); -} - -/*! - * @brief This function returns a constant reference to member child_frame_id - * @return Constant reference to member child_frame_id - */ -const std::string& geometry_msgs::msg::TransformStamped::child_frame_id() const -{ - return m_child_frame_id; -} - -/*! - * @brief This function returns a reference to member child_frame_id - * @return Reference to member child_frame_id - */ -std::string& geometry_msgs::msg::TransformStamped::child_frame_id() -{ - return m_child_frame_id; -} - -/*! - * @brief This function copies the value in member transform - * @param _transform New value to be copied in member transform - */ -void geometry_msgs::msg::TransformStamped::transform( - const geometry_msgs::msg::Transform& _transform) -{ - m_transform = _transform; -} - -/*! - * @brief This function moves the value in member transform - * @param _transform New value to be moved in member transform - */ -void geometry_msgs::msg::TransformStamped::transform( - geometry_msgs::msg::Transform&& _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::Transform& geometry_msgs::msg::TransformStamped::transform() const -{ - return m_transform; -} - -/*! - * @brief This function returns a reference to member transform - * @return Reference to member transform - */ -geometry_msgs::msg::Transform& geometry_msgs::msg::TransformStamped::transform() -{ - return m_transform; -} - -size_t geometry_msgs::msg::TransformStamped::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return geometry_msgs_msg_TransformStamped_max_key_cdr_typesize; -} - -bool geometry_msgs::msg::TransformStamped::isKeyDefined() -{ - return false; -} - -void geometry_msgs::msg::TransformStamped::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/TransformStamped.h b/LibCarla/source/carla/ros2/types/TransformStamped.h deleted file mode 100644 index a5f1fd27e6f..00000000000 --- a/LibCarla/source/carla/ros2/types/TransformStamped.h +++ /dev/null @@ -1,268 +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 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 "Header.h" -#include "Transform.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/types/TransformStampedPubSubTypes.cpp deleted file mode 100644 index afb9fb31ae7..00000000000 --- a/LibCarla/source/carla/ros2/types/TransformStampedPubSubTypes.cpp +++ /dev/null @@ -1,172 +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 TransformStampedPubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "TransformStampedPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace geometry_msgs { - namespace msg { - TransformStampedPubSubType::TransformStampedPubSubType() - { - setName("geometry_msgs::msg::dds_::TransformStamped_"); - auto type_size = TransformStamped::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = TransformStamped::isKeyDefined(); - size_t keyLength = TransformStamped::getKeyMaxCdrSerializedSize() > 16 ? - TransformStamped::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - TransformStampedPubSubType::~TransformStampedPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool TransformStampedPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - TransformStamped* 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 TransformStampedPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //Convert DATA to pointer of your type - TransformStamped* 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; - } - - std::function TransformStampedPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* TransformStampedPubSubType::createData() - { - return reinterpret_cast(new TransformStamped()); - } - - void TransformStampedPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool TransformStampedPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - TransformStamped* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - TransformStamped::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || TransformStamped::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/TransformStampedPubSubTypes.h b/LibCarla/source/carla/ros2/types/TransformStampedPubSubTypes.h deleted file mode 100644 index 7bd5a9b400f..00000000000 --- a/LibCarla/source/carla/ros2/types/TransformStampedPubSubTypes.h +++ /dev/null @@ -1,109 +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 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 "HeaderPubSubTypes.h" -#include "TransformPubSubTypes.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; - }; - } -} - -#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/types/Twist.cpp deleted file mode 100644 index 553921f89c8..00000000000 --- a/LibCarla/source/carla/ros2/types/Twist.cpp +++ /dev/null @@ -1,219 +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 Twist.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 "Twist.h" -#include - -#include -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() -{ -} - -geometry_msgs::msg::Twist::~Twist() -{ -} - -geometry_msgs::msg::Twist::Twist( - const Twist& x) -{ - m_linear = x.m_linear; - m_angular = x.m_angular; -} - -geometry_msgs::msg::Twist::Twist( - Twist&& x) noexcept -{ - m_linear = std::move(x.m_linear); - m_angular = std::move(x.m_angular); -} - -geometry_msgs::msg::Twist& geometry_msgs::msg::Twist::operator =( - const Twist& x) -{ - m_linear = x.m_linear; - m_angular = x.m_angular; - - return *this; -} - -geometry_msgs::msg::Twist& geometry_msgs::msg::Twist::operator =( - Twist&& x) noexcept -{ - m_linear = std::move(x.m_linear); - m_angular = std::move(x.m_angular); - - return *this; -} - -bool geometry_msgs::msg::Twist::operator ==( - const Twist& x) const -{ - return (m_linear == x.m_linear && m_angular == x.m_angular); -} - -bool geometry_msgs::msg::Twist::operator !=( - const Twist& x) const -{ - return !(*this == x); -} - -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 geometry_msgs::msg::Twist::getCdrSerializedSize( - const geometry_msgs::msg::Twist& data, - size_t current_alignment) -{ - 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::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; -} - -/*! - * @brief This function copies the value in member linear - * @param _linear New value to be copied in member linear - */ -void geometry_msgs::msg::Twist::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::Twist::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::Twist::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::Twist::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::Twist::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::Twist::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::Twist::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::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; -} - -bool geometry_msgs::msg::Twist::isKeyDefined() -{ - return false; -} - -void geometry_msgs::msg::Twist::serializeKey( - eprosima::fastcdr::Cdr& scdr) const -{ - (void) scdr; -} diff --git a/LibCarla/source/carla/ros2/types/Twist.h b/LibCarla/source/carla/ros2/types/Twist.h deleted file mode 100644 index 402ed9845fe..00000000000 --- a/LibCarla/source/carla/ros2/types/Twist.h +++ /dev/null @@ -1,240 +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 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_ diff --git a/LibCarla/source/carla/ros2/types/TwistPubSubTypes.cpp b/LibCarla/source/carla/ros2/types/TwistPubSubTypes.cpp deleted file mode 100644 index 5cabda52668..00000000000 --- a/LibCarla/source/carla/ros2/types/TwistPubSubTypes.cpp +++ /dev/null @@ -1,172 +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.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "TwistPubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace geometry_msgs { - namespace msg { - TwistPubSubType::TwistPubSubType() - { - setName("geometry_msgs::msg::dds_::Twist_"); - auto type_size = Twist::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Twist::isKeyDefined(); - size_t keyLength = Twist::getKeyMaxCdrSerializedSize() > 16 ? - Twist::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - TwistPubSubType::~TwistPubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool TwistPubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Twist* 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 TwistPubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //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 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; - } - - std::function TwistPubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* TwistPubSubType::createData() - { - return reinterpret_cast(new Twist()); - } - - void TwistPubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool TwistPubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Twist* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Twist::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Twist::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/TwistPubSubTypes.h b/LibCarla/source/carla/ros2/types/TwistPubSubTypes.h deleted file mode 100644 index d98a2d18445..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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*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/TwistWithCovariance.cpp b/LibCarla/source/carla/ros2/types/TwistWithCovariance.cpp deleted file mode 100644 index 332f228efba..00000000000 --- a/LibCarla/source/carla/ros2/types/TwistWithCovariance.cpp +++ /dev/null @@ -1,224 +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 TwistWithCovariance.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 "TwistWithCovariance.h" -#include - -#include -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 - - // geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36 m_covariance - memset(&m_covariance, 0, (36) * 8); -} - -geometry_msgs::msg::TwistWithCovariance::~TwistWithCovariance() -{ -} - -geometry_msgs::msg::TwistWithCovariance::TwistWithCovariance( - const TwistWithCovariance& x) -{ - m_twist = x.m_twist; - m_covariance = x.m_covariance; -} - -geometry_msgs::msg::TwistWithCovariance::TwistWithCovariance( - TwistWithCovariance&& x) noexcept -{ - m_twist = std::move(x.m_twist); - m_covariance = std::move(x.m_covariance); -} - -geometry_msgs::msg::TwistWithCovariance& geometry_msgs::msg::TwistWithCovariance::operator =( - const TwistWithCovariance& x) -{ - m_twist = x.m_twist; - m_covariance = x.m_covariance; - - return *this; -} - -geometry_msgs::msg::TwistWithCovariance& geometry_msgs::msg::TwistWithCovariance::operator =( - TwistWithCovariance&& x) noexcept -{ - m_twist = std::move(x.m_twist); - m_covariance = std::move(x.m_covariance); - - return *this; -} - -bool geometry_msgs::msg::TwistWithCovariance::operator ==( - const TwistWithCovariance& x) const -{ - return (m_twist == x.m_twist && m_covariance == x.m_covariance); -} - -bool geometry_msgs::msg::TwistWithCovariance::operator !=( - const TwistWithCovariance& x) const -{ - return !(*this == x); -} - -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 geometry_msgs::msg::TwistWithCovariance::getCdrSerializedSize( - const geometry_msgs::msg::TwistWithCovariance& data, - size_t current_alignment) -{ - 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); - - return current_alignment - initial_alignment; -} - -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; -} - -/*! - * @brief This function copies the value in member twist - * @param _twist New value to be copied in member twist - */ -void geometry_msgs::msg::TwistWithCovariance::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 geometry_msgs::msg::TwistWithCovariance::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& geometry_msgs::msg::TwistWithCovariance::twist() const -{ - return m_twist; -} - -/*! - * @brief This function returns a reference to member twist - * @return Reference to member twist - */ -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) -{ - 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::TwistWithCovariance::covariance( - geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_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::geometry_msgs__TwistWithCovariance__double_array_36& geometry_msgs::msg::TwistWithCovariance::covariance() const -{ - return m_covariance; -} - -/*! - * @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() -{ - return m_covariance; -} - -size_t geometry_msgs::msg::TwistWithCovariance::getKeyMaxCdrSerializedSize( - size_t current_alignment) -{ - static_cast(current_alignment); - return geometry_msgs_msg_TwistWithCovariance_max_key_cdr_typesize; -} - -bool geometry_msgs::msg::TwistWithCovariance::isKeyDefined() -{ - return false; -} - -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/types/TwistWithCovariance.h deleted file mode 100644 index 4aa2477567d..00000000000 --- a/LibCarla/source/carla/ros2/types/TwistWithCovariance.h +++ /dev/null @@ -1,242 +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 TwistWithCovariance.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_TWISTWITHCOVARIANCE_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_H_ - -#include "Twist.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(TwistWithCovariance_SOURCE) -#define TwistWithCovariance_DllAPI __declspec( dllexport ) -#else -#define TwistWithCovariance_DllAPI __declspec( dllimport ) -#endif // TwistWithCovariance_SOURCE -#else -#define TwistWithCovariance_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define TwistWithCovariance_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - - -namespace geometry_msgs { - namespace msg { - typedef std::array geometry_msgs__TwistWithCovariance__double_array_36; - /*! - * @brief This class represents the structure TwistWithCovariance defined by the user in the IDL file. - * @ingroup TWISTWITHCOVARIANCE - */ - class TwistWithCovariance - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport TwistWithCovariance(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~TwistWithCovariance(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object geometry_msgs::msg::TwistWithCovariance that will be copied. - */ - eProsima_user_DllExport TwistWithCovariance( - const TwistWithCovariance& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object geometry_msgs::msg::TwistWithCovariance that will be copied. - */ - eProsima_user_DllExport TwistWithCovariance( - TwistWithCovariance&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object geometry_msgs::msg::TwistWithCovariance that will be copied. - */ - eProsima_user_DllExport TwistWithCovariance& operator =( - const TwistWithCovariance& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object geometry_msgs::msg::TwistWithCovariance that will be copied. - */ - eProsima_user_DllExport TwistWithCovariance& operator =( - TwistWithCovariance&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::TwistWithCovariance object to compare. - */ - eProsima_user_DllExport bool operator ==( - const TwistWithCovariance& x) const; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::TwistWithCovariance object to compare. - */ - eProsima_user_DllExport bool operator !=( - const TwistWithCovariance& x) const; - - /*! - * @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 covariance - * @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); - - /*! - * @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); - - /*! - * @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; - - /*! - * @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(); - - /*! - * @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::TwistWithCovariance& 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::Twist m_twist; - geometry_msgs::msg::geometry_msgs__TwistWithCovariance__double_array_36 m_covariance; - }; - } // namespace msg -} // namespace geometry_msgs - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_TWISTWITHCOVARIANCE_H_ diff --git a/LibCarla/source/carla/ros2/types/TwistWithCovariancePubSubTypes.cpp b/LibCarla/source/carla/ros2/types/TwistWithCovariancePubSubTypes.cpp deleted file mode 100644 index e9c062decfa..00000000000 --- a/LibCarla/source/carla/ros2/types/TwistWithCovariancePubSubTypes.cpp +++ /dev/null @@ -1,173 +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.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "TwistWithCovariancePubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace geometry_msgs { - namespace msg { - - TwistWithCovariancePubSubType::TwistWithCovariancePubSubType() - { - setName("geometry_msgs::msg::dds_::TwistWithCovariance_"); - auto type_size = TwistWithCovariance::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = TwistWithCovariance::isKeyDefined(); - size_t keyLength = TwistWithCovariance::getKeyMaxCdrSerializedSize() > 16 ? - TwistWithCovariance::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - TwistWithCovariancePubSubType::~TwistWithCovariancePubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool TwistWithCovariancePubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - TwistWithCovariance* 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 TwistWithCovariancePubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //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 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; - } - - std::function TwistWithCovariancePubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* TwistWithCovariancePubSubType::createData() - { - return reinterpret_cast(new TwistWithCovariance()); - } - - void TwistWithCovariancePubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool TwistWithCovariancePubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - TwistWithCovariance* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - TwistWithCovariance::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || TwistWithCovariance::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/TwistWithCovariancePubSubTypes.h b/LibCarla/source/carla/ros2/types/TwistWithCovariancePubSubTypes.h deleted file mode 100644 index f0335e42253..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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*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/Vector3.cpp b/LibCarla/source/carla/ros2/types/Vector3.cpp deleted file mode 100644 index 2890489abfc..00000000000 --- a/LibCarla/source/carla/ros2/types/Vector3.cpp +++ /dev/null @@ -1,239 +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 Vector3.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 "Vector3.h" -#include - -#include -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 = 0.0; - // double m_y - m_y = 0.0; - // double m_z - m_z = 0.0; -} - -geometry_msgs::msg::Vector3::~Vector3() -{ -} - -geometry_msgs::msg::Vector3::Vector3( - const Vector3& x) -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; -} - -geometry_msgs::msg::Vector3::Vector3( - Vector3&& x) noexcept -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; -} - -geometry_msgs::msg::Vector3& geometry_msgs::msg::Vector3::operator =( - const Vector3& x) -{ - - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; - - return *this; -} - -geometry_msgs::msg::Vector3& geometry_msgs::msg::Vector3::operator =( - Vector3&& x) noexcept -{ - m_x = x.m_x; - m_y = x.m_y; - m_z = x.m_z; - - return *this; -} - -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); -} - -bool geometry_msgs::msg::Vector3::operator !=( - const Vector3& x) const -{ - return !(*this == x); -} - -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 geometry_msgs::msg::Vector3::getCdrSerializedSize( - const geometry_msgs::msg::Vector3& data, - size_t current_alignment) -{ - (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; -} - -/*! - * @brief This function sets a value in member x - * @param _x New value for member x - */ -void geometry_msgs::msg::Vector3::x( - double _x) -{ - m_x = _x; -} - -/*! - * @brief This function returns the value of member x - * @return Value of member x - */ -double geometry_msgs::msg::Vector3::x() const -{ - return m_x; -} - -/*! - * @brief This function returns a reference to member x - * @return Reference to member x - */ -double& geometry_msgs::msg::Vector3::x() -{ - return m_x; -} - -/*! - * @brief This function sets a value in member y - * @param _y New value for member y - */ -void geometry_msgs::msg::Vector3::y( - double _y) -{ - m_y = _y; -} - -/*! - * @brief This function returns the value of member y - * @return Value of member y - */ -double geometry_msgs::msg::Vector3::y() const -{ - return m_y; -} - -/*! - * @brief This function returns a reference to member y - * @return Reference to member y - */ -double& geometry_msgs::msg::Vector3::y() -{ - return m_y; -} - -/*! - * @brief This function sets a value in member z - * @param _z New value for member z - */ -void geometry_msgs::msg::Vector3::z( - double _z) -{ - m_z = _z; -} - -/*! - * @brief This function returns the value of member z - * @return Value of member z - */ -double geometry_msgs::msg::Vector3::z() const -{ - return m_z; -} - -/*! - * @brief This function returns a reference to member z - * @return Reference to member z - */ -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; -} - -bool geometry_msgs::msg::Vector3::isKeyDefined() -{ - return false; -} - -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/types/Vector3.h deleted file mode 100644 index cb96d7843a0..00000000000 --- a/LibCarla/source/carla/ros2/types/Vector3.h +++ /dev/null @@ -1,246 +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 Vector3.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_VECTOR3_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_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(Vector3_SOURCE) -#define Vector3_DllAPI __declspec( dllexport ) -#else -#define Vector3_DllAPI __declspec( dllimport ) -#endif // Vector3_SOURCE -#else -#define Vector3_DllAPI -#endif // EPROSIMA_USER_DLL_EXPORT -#else -#define Vector3_DllAPI -#endif // _WIN32 - -namespace eprosima { -namespace fastcdr { -class Cdr; -} // namespace fastcdr -} // namespace eprosima - - -namespace geometry_msgs { - namespace msg { - /*! - * @brief This class represents the structure Vector3 defined by the user in the IDL file. - * @ingroup VECTOR3 - */ - class Vector3 - { - public: - - /*! - * @brief Default constructor. - */ - eProsima_user_DllExport Vector3(); - - /*! - * @brief Default destructor. - */ - eProsima_user_DllExport ~Vector3(); - - /*! - * @brief Copy constructor. - * @param x Reference to the object geometry_msgs::msg::Vector3 that will be copied. - */ - eProsima_user_DllExport Vector3( - const Vector3& x); - - /*! - * @brief Move constructor. - * @param x Reference to the object geometry_msgs::msg::Vector3 that will be copied. - */ - eProsima_user_DllExport Vector3( - Vector3&& x) noexcept; - - /*! - * @brief Copy assignment. - * @param x Reference to the object geometry_msgs::msg::Vector3 that will be copied. - */ - eProsima_user_DllExport Vector3& operator =( - const Vector3& x); - - /*! - * @brief Move assignment. - * @param x Reference to the object geometry_msgs::msg::Vector3 that will be copied. - */ - eProsima_user_DllExport Vector3& operator =( - Vector3&& x) noexcept; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Vector3 object to compare. - */ - eProsima_user_DllExport bool operator ==( - const Vector3& x) const; - - /*! - * @brief Comparison operator. - * @param x geometry_msgs::msg::Vector3 object to compare. - */ - eProsima_user_DllExport bool operator !=( - const Vector3& 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 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::Vector3& 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; - }; - } // namespace msg -} // namespace geometry_msgs - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_H_ diff --git a/LibCarla/source/carla/ros2/types/Vector3PubSubTypes.cpp b/LibCarla/source/carla/ros2/types/Vector3PubSubTypes.cpp deleted file mode 100644 index 2a568e23a3f..00000000000 --- a/LibCarla/source/carla/ros2/types/Vector3PubSubTypes.cpp +++ /dev/null @@ -1,172 +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 Vector3PubSubTypes.cpp - * This header file contains the implementation of the serialization functions. - * - * This file was generated by the tool fastcdrgen. - */ - -#include -#include - -#include "Vector3PubSubTypes.h" - -using SerializedPayload_t = eprosima::fastrtps::rtps::SerializedPayload_t; -using InstanceHandle_t = eprosima::fastrtps::rtps::InstanceHandle_t; - -namespace geometry_msgs { - namespace msg { - Vector3PubSubType::Vector3PubSubType() - { - setName("geometry_msgs::msg::dds_::Vector3_"); - auto type_size = Vector3::getMaxCdrSerializedSize(); - type_size += eprosima::fastcdr::Cdr::alignment(type_size, 4); /* possible submessage alignment */ - m_typeSize = static_cast(type_size) + 4; /*encapsulation*/ - m_isGetKeyDefined = Vector3::isKeyDefined(); - size_t keyLength = Vector3::getKeyMaxCdrSerializedSize() > 16 ? - Vector3::getKeyMaxCdrSerializedSize() : 16; - m_keyBuffer = reinterpret_cast(malloc(keyLength)); - memset(m_keyBuffer, 0, keyLength); - } - - Vector3PubSubType::~Vector3PubSubType() - { - if (m_keyBuffer != nullptr) - { - free(m_keyBuffer); - } - } - - bool Vector3PubSubType::serialize( - void* data, - SerializedPayload_t* payload) - { - Vector3* 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 Vector3PubSubType::deserialize( - SerializedPayload_t* payload, - void* data) - { - try - { - //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 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; - } - - std::function Vector3PubSubType::getSerializedSizeProvider( - void* data) - { - return [data]() -> uint32_t - { - return static_cast(type::getCdrSerializedSize(*static_cast(data))) + - 4u /*encapsulation*/; - }; - } - - void* Vector3PubSubType::createData() - { - return reinterpret_cast(new Vector3()); - } - - void Vector3PubSubType::deleteData( - void* data) - { - delete(reinterpret_cast(data)); - } - - bool Vector3PubSubType::getKey( - void* data, - InstanceHandle_t* handle, - bool force_md5) - { - if (!m_isGetKeyDefined) - { - return false; - } - - Vector3* p_type = static_cast(data); - - // Object that manages the raw buffer. - eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast(m_keyBuffer), - Vector3::getKeyMaxCdrSerializedSize()); - - // Object that serializes the data. - eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS); - p_type->serializeKey(ser); - if (force_md5 || Vector3::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/Vector3PubSubTypes.h b/LibCarla/source/carla/ros2/types/Vector3PubSubTypes.h deleted file mode 100644 index 063b62908aa..00000000000 --- a/LibCarla/source/carla/ros2/types/Vector3PubSubTypes.h +++ /dev/null @@ -1,140 +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 Vector3PubSubTypes.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_VECTOR3_PUBSUBTYPES_H_ -#define _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_PUBSUBTYPES_H_ - -#include -#include - -#include "Vector3.h" - -#if !defined(GEN_API_VER) || (GEN_API_VER != 1) -#error \ - Generated Vector3 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 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 reinterpret_cast<::size_t>(&reinterpret_cast((static_cast(nullptr)->*get(Tag())))); - } - } - #endif - - /*! - * @brief This class represents the TopicDataType of the type Vector3 defined by the user in the IDL file. - * @ingroup VECTOR3 - */ - class Vector3PubSubType : public eprosima::fastdds::dds::TopicDataType - { - public: - - typedef Vector3 type; - - eProsima_user_DllExport Vector3PubSubType(); - - eProsima_user_DllExport virtual ~Vector3PubSubType() 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) Vector3(); - 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 24ULL == (detail::Vector3_offset_of() + sizeof(double)); - - }}; - } -} - -#endif // _FAST_DDS_GENERATED_GEOMETRY_MSGS_MSG_VECTOR3_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..89acd74f228 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/VehicleAckermannControl.h @@ -0,0 +1,61 @@ +// 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 "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..46cc0df3d19 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/VehicleActorDefinition.h @@ -0,0 +1,53 @@ +// 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/types/ActorDefinition.h" +#include "carla/ros2/types/Polygon.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/CarlaEgoVehicleStatus.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::CarlaEgoVehicleStatus_Constants::ACKERMANN_CONTROL; + case carla::rpc::VehicleControlType::VehicleControl: + default: + return carla_msgs::msg::CarlaEgoVehicleStatus_Constants::VEHICLE_CONTROL; + } +} + +struct VehicleActorDefinition : public ActorDefinition { + VehicleActorDefinition(ActorNameDefinition const &actor_name_definition, carla::geom::BoundingBox const &bounding_box, + rpc::VehiclePhysicsControl vehicle_physics_control_in) + : ActorDefinition(actor_name_definition, bounding_box) + , 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..5bc4aabdf85 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/VehicleControl.h @@ -0,0 +1,70 @@ +// 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/types/Timestamp.h" +#include "carla/rpc/VehicleControl.h" +#include "carla/sensor/data/ActorDynamicState.h" +#include "carla_msgs/msg/CarlaEgoVehicleControl.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + * VehicleControl: convert carla_msgs::msg::CarlaEgoVehicleControl into FVehicleControl without the need of + * knowing FVehicleControl class within LibCarla + */ +class VehicleControl { +public: + explicit VehicleControl(const carla_msgs::msg::CarlaEgoVehicleControl& 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::CarlaEgoVehicleControl 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::CarlaEgoVehicleControl _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..5489d5eb84a --- /dev/null +++ b/LibCarla/source/carla/ros2/types/WalkerActorDefinition.h @@ -0,0 +1,33 @@ +// 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/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(ActorNameDefinition const &actor_name_definition, carla::geom::BoundingBox const &bounding_box) + : ActorDefinition(actor_name_definition, bounding_box) {} + 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..2bf8e12eb06 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/WalkerControl.h @@ -0,0 +1,60 @@ +// 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/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/ros2/types/WeatherParameters.h b/LibCarla/source/carla/ros2/types/WeatherParameters.h new file mode 100644 index 00000000000..901490f4f49 --- /dev/null +++ b/LibCarla/source/carla/ros2/types/WeatherParameters.h @@ -0,0 +1,79 @@ +// 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/rpc/WeatherParameters.h" +#include "carla_msgs/msg/CarlaWeatherParameters.h" + +namespace carla { +namespace ros2 { +namespace types { + +/** + Convert a carla rpc WeatherParameters to ROS type + and holds carla time details +*/ +class WeatherParameters { +public: + explicit WeatherParameters(carla::rpc::WeatherParameters const &weather_parameters) { + _weather_parameters.cloudiness(weather_parameters.cloudiness); + _weather_parameters.precipitation(weather_parameters.precipitation); + _weather_parameters.precipitation_deposits(weather_parameters.precipitation_deposits); + _weather_parameters.wind_intensity(weather_parameters.wind_intensity); + _weather_parameters.sun_azimuth_angle(weather_parameters.sun_azimuth_angle); + _weather_parameters.sun_altitude_angle(weather_parameters.sun_altitude_angle); + _weather_parameters.fog_density(weather_parameters.fog_density); + _weather_parameters.fog_distance(weather_parameters.fog_distance); + _weather_parameters.fog_falloff(weather_parameters.fog_falloff); + _weather_parameters.wetness(weather_parameters.wetness); + _weather_parameters.scattering_intensity(weather_parameters.scattering_intensity); + _weather_parameters.mie_scattering_scale(weather_parameters.mie_scattering_scale); + _weather_parameters.rayleigh_scattering_scale(weather_parameters.rayleigh_scattering_scale); + _weather_parameters.dust_storm(weather_parameters.dust_storm); + } + + explicit WeatherParameters(carla_msgs::msg::CarlaWeatherParameters const &weather_parameters) + : _weather_parameters(weather_parameters) {} + + ~WeatherParameters() = default; + WeatherParameters(const WeatherParameters&) = default; + WeatherParameters& operator=(const WeatherParameters&) = default; + WeatherParameters(WeatherParameters&&) = default; + WeatherParameters& operator=(WeatherParameters&&) = default; + + carla::rpc::WeatherParameters weather_parameters_rpc() const { + carla::rpc::WeatherParameters weather_parameters; + weather_parameters.cloudiness = _weather_parameters.cloudiness(); + weather_parameters.precipitation = _weather_parameters.precipitation(); + weather_parameters.precipitation_deposits = _weather_parameters.precipitation_deposits(); + weather_parameters.wind_intensity = _weather_parameters.wind_intensity(); + weather_parameters.sun_azimuth_angle = _weather_parameters.sun_azimuth_angle(); + weather_parameters.sun_altitude_angle = _weather_parameters.sun_altitude_angle(); + weather_parameters.fog_density = _weather_parameters.fog_density(); + weather_parameters.fog_distance = _weather_parameters.fog_distance(); + weather_parameters.fog_falloff = _weather_parameters.fog_falloff(); + weather_parameters.wetness = _weather_parameters.wetness(); + weather_parameters.scattering_intensity = _weather_parameters.scattering_intensity(); + weather_parameters.mie_scattering_scale = _weather_parameters.mie_scattering_scale(); + weather_parameters.rayleigh_scattering_scale = _weather_parameters.rayleigh_scattering_scale(); + weather_parameters.dust_storm = _weather_parameters.dust_storm(); + return weather_parameters; + } + + /** + * The resulting ROS carla_msgs::msg::CarlaWeatherParameters + */ + const carla_msgs::msg::CarlaWeatherParameters& weather_parameters_msg() const { + return _weather_parameters; + } + +private: + carla_msgs::msg::CarlaWeatherParameters _weather_parameters; +}; +} // namespace types +} // namespace ros2 +} // namespace carla \ No newline at end of file diff --git a/LibCarla/source/carla/rpc/AckermannControllerSettings.h b/LibCarla/source/carla/rpc/AckermannControllerSettings.h index 06b79f93449..41b84856e2e 100644 --- a/LibCarla/source/carla/rpc/AckermannControllerSettings.h +++ b/LibCarla/source/carla/rpc/AckermannControllerSettings.h @@ -85,7 +85,7 @@ namespace rpc { accel_kp, accel_ki, accel_kd - ); + ) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/Actor.h b/LibCarla/source/carla/rpc/Actor.h index 7e75e97d53a..984713bf811 100644 --- a/LibCarla/source/carla/rpc/Actor.h +++ b/LibCarla/source/carla/rpc/Actor.h @@ -51,7 +51,7 @@ namespace rpc { /// @} - MSGPACK_DEFINE_ARRAY(id, parent_id, description, bounding_box, semantic_tags, stream_token); + MSGPACK_DEFINE_ARRAY(id, parent_id, description, bounding_box, semantic_tags, stream_token) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/ActorAttribute.h b/LibCarla/source/carla/rpc/ActorAttribute.h index 8643751aa75..104069fcc61 100644 --- a/LibCarla/source/carla/rpc/ActorAttribute.h +++ b/LibCarla/source/carla/rpc/ActorAttribute.h @@ -12,7 +12,7 @@ #include -MSGPACK_ADD_ENUM(carla::rpc::ActorAttributeType); +MSGPACK_ADD_ENUM(carla::rpc::ActorAttributeType) #ifdef LIBCARLA_INCLUDED_FROM_UE4 #include @@ -64,7 +64,7 @@ namespace rpc { #endif // LIBCARLA_INCLUDED_FROM_UE4 - MSGPACK_DEFINE_ARRAY(id, type, value, recommended_values, is_modifiable, restrict_to_recommended); + MSGPACK_DEFINE_ARRAY(id, type, value, recommended_values, is_modifiable, restrict_to_recommended) }; class ActorAttributeValue { @@ -98,7 +98,7 @@ namespace rpc { #endif // LIBCARLA_INCLUDED_FROM_UE4 - MSGPACK_DEFINE_ARRAY(id, type, value); + MSGPACK_DEFINE_ARRAY(id, type, value) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/ActorDefinition.h b/LibCarla/source/carla/rpc/ActorDefinition.h index 6d9debcaa0b..89ec3fbd711 100644 --- a/LibCarla/source/carla/rpc/ActorDefinition.h +++ b/LibCarla/source/carla/rpc/ActorDefinition.h @@ -52,7 +52,7 @@ namespace rpc { #endif // LIBCARLA_INCLUDED_FROM_UE4 - MSGPACK_DEFINE_ARRAY(uid, id, tags, attributes); + MSGPACK_DEFINE_ARRAY(uid, id, tags, attributes) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/ActorDescription.h b/LibCarla/source/carla/rpc/ActorDescription.h index 0415c5100e3..297d3e6b858 100644 --- a/LibCarla/source/carla/rpc/ActorDescription.h +++ b/LibCarla/source/carla/rpc/ActorDescription.h @@ -58,7 +58,7 @@ namespace rpc { #endif // LIBCARLA_INCLUDED_FROM_UE4 - MSGPACK_DEFINE_ARRAY(uid, id, attributes); + MSGPACK_DEFINE_ARRAY(uid, id, attributes) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/AttachmentType.h b/LibCarla/source/carla/rpc/AttachmentType.h index a18704abab8..20d8102ae96 100644 --- a/LibCarla/source/carla/rpc/AttachmentType.h +++ b/LibCarla/source/carla/rpc/AttachmentType.h @@ -25,4 +25,4 @@ namespace rpc { } // namespace rpc } // namespace carla -MSGPACK_ADD_ENUM(carla::rpc::AttachmentType); +MSGPACK_ADD_ENUM(carla::rpc::AttachmentType) diff --git a/LibCarla/source/carla/rpc/BoneTransformDataOut.h b/LibCarla/source/carla/rpc/BoneTransformDataOut.h index 0366ff1110c..05100465cce 100644 --- a/LibCarla/source/carla/rpc/BoneTransformDataOut.h +++ b/LibCarla/source/carla/rpc/BoneTransformDataOut.h @@ -36,7 +36,7 @@ namespace rpc { } - MSGPACK_DEFINE_ARRAY(bone_name, world, component, relative); + MSGPACK_DEFINE_ARRAY(bone_name, world, component, relative) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/Color.h b/LibCarla/source/carla/rpc/Color.h index 85058b495c8..ca18a9fe4ac 100644 --- a/LibCarla/source/carla/rpc/Color.h +++ b/LibCarla/source/carla/rpc/Color.h @@ -57,7 +57,7 @@ namespace rpc { #endif // LIBCARLA_INCLUDED_FROM_UE4 - MSGPACK_DEFINE_ARRAY(r, g, b); + MSGPACK_DEFINE_ARRAY(r, g, b) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/Command.h b/LibCarla/source/carla/rpc/Command.h index ab117c971e3..751188e7d1f 100644 --- a/LibCarla/source/carla/rpc/Command.h +++ b/LibCarla/source/carla/rpc/Command.h @@ -74,7 +74,7 @@ namespace rpc { AttachmentType attachment_type; std::string socket_name; std::vector do_after; - MSGPACK_DEFINE_ARRAY(description, transform, parent, attachment_type, socket_name, do_after); + MSGPACK_DEFINE_ARRAY(description, transform, parent, attachment_type, socket_name, do_after) }; struct DestroyActor : CommandBase { @@ -82,7 +82,7 @@ namespace rpc { DestroyActor(ActorId id) : actor(id) {} ActorId actor; - MSGPACK_DEFINE_ARRAY(actor); + MSGPACK_DEFINE_ARRAY(actor) }; struct ApplyVehicleControl : CommandBase { @@ -92,7 +92,7 @@ namespace rpc { control(value) {} ActorId actor; VehicleControl control; - MSGPACK_DEFINE_ARRAY(actor, control); + MSGPACK_DEFINE_ARRAY(actor, control) }; struct ApplyVehicleAckermannControl : CommandBase { @@ -102,7 +102,7 @@ namespace rpc { control(value) {} ActorId actor; VehicleAckermannControl control; - MSGPACK_DEFINE_ARRAY(actor, control); + MSGPACK_DEFINE_ARRAY(actor, control) }; struct ApplyWalkerControl : CommandBase { @@ -112,7 +112,7 @@ namespace rpc { control(value) {} ActorId actor; WalkerControl control; - MSGPACK_DEFINE_ARRAY(actor, control); + MSGPACK_DEFINE_ARRAY(actor, control) }; struct ApplyVehiclePhysicsControl : CommandBase { @@ -122,7 +122,7 @@ namespace rpc { physics_control(value) {} ActorId actor; VehiclePhysicsControl physics_control; - MSGPACK_DEFINE_ARRAY(actor, physics_control); + MSGPACK_DEFINE_ARRAY(actor, physics_control) }; struct ApplyTransform : CommandBase { @@ -132,7 +132,7 @@ namespace rpc { transform(value) {} ActorId actor; geom::Transform transform; - MSGPACK_DEFINE_ARRAY(actor, transform); + MSGPACK_DEFINE_ARRAY(actor, transform) }; struct ApplyLocation : CommandBase { @@ -142,7 +142,7 @@ namespace rpc { location(value) {} ActorId actor; geom::Location location; - MSGPACK_DEFINE_ARRAY(actor, location); + MSGPACK_DEFINE_ARRAY(actor, location) }; struct ApplyWalkerState : CommandBase { @@ -151,7 +151,7 @@ namespace rpc { ActorId actor; geom::Transform transform; float speed; - MSGPACK_DEFINE_ARRAY(actor, transform, speed); + MSGPACK_DEFINE_ARRAY(actor, transform, speed) }; struct ApplyTargetVelocity : CommandBase { @@ -161,7 +161,7 @@ namespace rpc { velocity(value) {} ActorId actor; geom::Vector3D velocity; - MSGPACK_DEFINE_ARRAY(actor, velocity); + MSGPACK_DEFINE_ARRAY(actor, velocity) }; struct ApplyTargetAngularVelocity : CommandBase { @@ -171,7 +171,7 @@ namespace rpc { angular_velocity(value) {} ActorId actor; geom::Vector3D angular_velocity; - MSGPACK_DEFINE_ARRAY(actor, angular_velocity); + MSGPACK_DEFINE_ARRAY(actor, angular_velocity) }; struct ApplyImpulse : CommandBase { @@ -181,7 +181,7 @@ namespace rpc { impulse(value) {} ActorId actor; geom::Vector3D impulse; - MSGPACK_DEFINE_ARRAY(actor, impulse); + MSGPACK_DEFINE_ARRAY(actor, impulse) }; struct ApplyForce : CommandBase { @@ -191,7 +191,7 @@ namespace rpc { force(value) {} ActorId actor; geom::Vector3D force; - MSGPACK_DEFINE_ARRAY(actor, force); + MSGPACK_DEFINE_ARRAY(actor, force) }; struct ApplyAngularImpulse : CommandBase { @@ -201,7 +201,7 @@ namespace rpc { impulse(value) {} ActorId actor; geom::Vector3D impulse; - MSGPACK_DEFINE_ARRAY(actor, impulse); + MSGPACK_DEFINE_ARRAY(actor, impulse) }; struct ApplyTorque : CommandBase { @@ -211,7 +211,7 @@ namespace rpc { torque(value) {} ActorId actor; geom::Vector3D torque; - MSGPACK_DEFINE_ARRAY(actor, torque); + MSGPACK_DEFINE_ARRAY(actor, torque) }; struct SetSimulatePhysics : CommandBase { @@ -221,7 +221,7 @@ namespace rpc { enabled(value) {} ActorId actor; bool enabled; - MSGPACK_DEFINE_ARRAY(actor, enabled); + MSGPACK_DEFINE_ARRAY(actor, enabled) }; struct SetEnableGravity : CommandBase { @@ -231,7 +231,7 @@ namespace rpc { enabled(value) {} ActorId actor; bool enabled; - MSGPACK_DEFINE_ARRAY(actor, enabled); + MSGPACK_DEFINE_ARRAY(actor, enabled) }; struct SetAutopilot : CommandBase { @@ -246,7 +246,7 @@ namespace rpc { ActorId actor; bool enabled; uint16_t tm_port; - MSGPACK_DEFINE_ARRAY(actor, enabled); + MSGPACK_DEFINE_ARRAY(actor, enabled) }; struct ShowDebugTelemetry : CommandBase { @@ -258,7 +258,7 @@ namespace rpc { enabled(value) {} ActorId actor; bool enabled; - MSGPACK_DEFINE_ARRAY(actor, enabled); + MSGPACK_DEFINE_ARRAY(actor, enabled) }; struct SetVehicleLightState : CommandBase { @@ -270,14 +270,14 @@ namespace rpc { light_state(value) {} ActorId actor; VehicleLightState::flag_type light_state; - MSGPACK_DEFINE_ARRAY(actor, light_state); + MSGPACK_DEFINE_ARRAY(actor, light_state) }; struct ConsoleCommand : CommandBase { ConsoleCommand() = default; ConsoleCommand(std::string cmd) : cmd(cmd) {} std::string cmd; - MSGPACK_DEFINE_ARRAY(cmd); + MSGPACK_DEFINE_ARRAY(cmd) }; struct SetTrafficLightState : CommandBase { @@ -289,7 +289,7 @@ namespace rpc { traffic_light_state(state) {} ActorId actor; rpc::TrafficLightState traffic_light_state; - MSGPACK_DEFINE_ARRAY(actor, traffic_light_state); + MSGPACK_DEFINE_ARRAY(actor, traffic_light_state) }; using CommandType = boost::variant2::variant< @@ -318,7 +318,7 @@ namespace rpc { CommandType command; - MSGPACK_DEFINE_ARRAY(command); + MSGPACK_DEFINE_ARRAY(command) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/CustomV2XBytes.h b/LibCarla/source/carla/rpc/CustomV2XBytes.h index dd36c56eec6..3a0a1ed7f9d 100644 --- a/LibCarla/source/carla/rpc/CustomV2XBytes.h +++ b/LibCarla/source/carla/rpc/CustomV2XBytes.h @@ -22,7 +22,7 @@ class CustomV2XBytes } uint8_t data_size{0u}; std::array bytes; - MSGPACK_DEFINE_ARRAY(data_size, bytes); + MSGPACK_DEFINE_ARRAY(data_size, bytes) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/DebugShape.h b/LibCarla/source/carla/rpc/DebugShape.h index d6306a1f273..57309eade2a 100644 --- a/LibCarla/source/carla/rpc/DebugShape.h +++ b/LibCarla/source/carla/rpc/DebugShape.h @@ -32,60 +32,60 @@ namespace rpc { struct Point { geom::Location location; float size; - MSGPACK_DEFINE_ARRAY(location, size); + MSGPACK_DEFINE_ARRAY(location, size) }; struct HUDPoint { geom::Location location; float size; - MSGPACK_DEFINE_ARRAY(location, size); + MSGPACK_DEFINE_ARRAY(location, size) }; struct Line { geom::Location begin; geom::Location end; float thickness; - MSGPACK_DEFINE_ARRAY(begin, end, thickness); + MSGPACK_DEFINE_ARRAY(begin, end, thickness) }; struct HUDLine { geom::Location begin; geom::Location end; float thickness; - MSGPACK_DEFINE_ARRAY(begin, end, thickness); + MSGPACK_DEFINE_ARRAY(begin, end, thickness) }; struct Arrow { Line line; float arrow_size; - MSGPACK_DEFINE_ARRAY(line, arrow_size); + MSGPACK_DEFINE_ARRAY(line, arrow_size) }; struct HUDArrow { HUDLine line; float arrow_size; - MSGPACK_DEFINE_ARRAY(line, arrow_size); + MSGPACK_DEFINE_ARRAY(line, arrow_size) }; struct Box { geom::BoundingBox box; geom::Rotation rotation; float thickness; - MSGPACK_DEFINE_ARRAY(box, rotation, thickness); + MSGPACK_DEFINE_ARRAY(box, rotation, thickness) }; struct HUDBox { geom::BoundingBox box; geom::Rotation rotation; float thickness; - MSGPACK_DEFINE_ARRAY(box, rotation, thickness); + MSGPACK_DEFINE_ARRAY(box, rotation, thickness) }; struct String { geom::Location location; std::string text; bool draw_shadow; - MSGPACK_DEFINE_ARRAY(location, text, draw_shadow); + MSGPACK_DEFINE_ARRAY(location, text, draw_shadow) }; boost::variant2::variant primitive; @@ -96,7 +96,7 @@ namespace rpc { bool persistent_lines = true; - MSGPACK_DEFINE_ARRAY(primitive, color, life_time, persistent_lines); + MSGPACK_DEFINE_ARRAY(primitive, color, life_time, persistent_lines) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/EnvironmentObject.h b/LibCarla/source/carla/rpc/EnvironmentObject.h index 45ed58388aa..c50d2635a6f 100644 --- a/LibCarla/source/carla/rpc/EnvironmentObject.h +++ b/LibCarla/source/carla/rpc/EnvironmentObject.h @@ -14,6 +14,12 @@ #include "carla/rpc/Transform.h" #include "carla/rpc/ObjectLabel.h" +#ifdef LIBCARLA_INCLUDED_FROM_UE4 +#include +#include "Carla/Util/EnvironmentObject.h" +#include +#endif // LIBCARLA_INCLUDED_FROM_UE4 + namespace carla { namespace rpc { @@ -36,7 +42,7 @@ namespace rpc { #endif // LIBCARLA_INCLUDED_FROM_UE4 - MSGPACK_DEFINE_ARRAY(transform, bounding_box, id, name, type); + MSGPACK_DEFINE_ARRAY(transform, bounding_box, id, name, type) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/EpisodeInfo.h b/LibCarla/source/carla/rpc/EpisodeInfo.h index a24eac3f719..f1ab2620ee8 100644 --- a/LibCarla/source/carla/rpc/EpisodeInfo.h +++ b/LibCarla/source/carla/rpc/EpisodeInfo.h @@ -25,7 +25,7 @@ namespace rpc { streaming::Token token; - MSGPACK_DEFINE_ARRAY(id, token); + MSGPACK_DEFINE_ARRAY(id, token) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/EpisodeSettings.h b/LibCarla/source/carla/rpc/EpisodeSettings.h index a346ce24c79..039bf9c710f 100644 --- a/LibCarla/source/carla/rpc/EpisodeSettings.h +++ b/LibCarla/source/carla/rpc/EpisodeSettings.h @@ -51,7 +51,7 @@ namespace rpc { MSGPACK_DEFINE_ARRAY(synchronous_mode, no_rendering_mode, fixed_delta_seconds, substepping, max_substep_delta_time, max_substeps, max_culling_distance, deterministic_ragdolls, - tile_stream_distance, actor_active_distance, spectator_as_ego); + tile_stream_distance, actor_active_distance, spectator_as_ego) // ========================================================================= // -- Constructors --------------------------------------------------------- diff --git a/LibCarla/source/carla/rpc/FloatColor.h b/LibCarla/source/carla/rpc/FloatColor.h index 32c68609650..6cf544fa004 100644 --- a/LibCarla/source/carla/rpc/FloatColor.h +++ b/LibCarla/source/carla/rpc/FloatColor.h @@ -66,7 +66,7 @@ namespace rpc { #endif // LIBCARLA_INCLUDED_FROM_UE4 - MSGPACK_DEFINE_ARRAY(r, g, b, a); + MSGPACK_DEFINE_ARRAY(r, g, b, a) }; #pragma pack(pop) diff --git a/LibCarla/source/carla/rpc/LabelledPoint.h b/LibCarla/source/carla/rpc/LabelledPoint.h index 9cf5ee75149..5ba5d2d8cf4 100644 --- a/LibCarla/source/carla/rpc/LabelledPoint.h +++ b/LibCarla/source/carla/rpc/LabelledPoint.h @@ -24,7 +24,7 @@ namespace rpc { CityObjectLabel _label; - MSGPACK_DEFINE_ARRAY(_location, _label); + MSGPACK_DEFINE_ARRAY(_location, _label) }; diff --git a/LibCarla/source/carla/rpc/LightState.h b/LibCarla/source/carla/rpc/LightState.h index aaae071e37b..31256126682 100644 --- a/LibCarla/source/carla/rpc/LightState.h +++ b/LibCarla/source/carla/rpc/LightState.h @@ -49,7 +49,7 @@ class LightState { Color _color; bool _active = false; - MSGPACK_DEFINE_ARRAY(_id, _location, _intensity, _group, _color, _active); + MSGPACK_DEFINE_ARRAY(_id, _location, _intensity, _group, _color, _active) }; diff --git a/LibCarla/source/carla/rpc/MapInfo.h b/LibCarla/source/carla/rpc/MapInfo.h index 7b6ad1af492..43d870e2690 100644 --- a/LibCarla/source/carla/rpc/MapInfo.h +++ b/LibCarla/source/carla/rpc/MapInfo.h @@ -22,7 +22,7 @@ namespace rpc { std::vector recommended_spawn_points; - MSGPACK_DEFINE_ARRAY(name, recommended_spawn_points); + MSGPACK_DEFINE_ARRAY(name, recommended_spawn_points) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/MapLayer.h b/LibCarla/source/carla/rpc/MapLayer.h index c9eb6007abd..3f2748bbf86 100644 --- a/LibCarla/source/carla/rpc/MapLayer.h +++ b/LibCarla/source/carla/rpc/MapLayer.h @@ -35,4 +35,4 @@ std::string MapLayerToString(MapLayer MapLayerValue); } // namespace rpc } // namespace carla -MSGPACK_ADD_ENUM(carla::rpc::MapLayer); +MSGPACK_ADD_ENUM(carla::rpc::MapLayer) diff --git a/LibCarla/source/carla/rpc/MaterialParameter.h b/LibCarla/source/carla/rpc/MaterialParameter.h index 872d6aa03e3..22c3452deb3 100644 --- a/LibCarla/source/carla/rpc/MaterialParameter.h +++ b/LibCarla/source/carla/rpc/MaterialParameter.h @@ -26,4 +26,4 @@ std::string MaterialParameterToString(MaterialParameter material_parameter); } // namespace rpc } // namespace carla -MSGPACK_ADD_ENUM(carla::rpc::MaterialParameter); +MSGPACK_ADD_ENUM(carla::rpc::MaterialParameter) diff --git a/LibCarla/source/carla/rpc/Metadata.h b/LibCarla/source/carla/rpc/Metadata.h index 30a3d3f4191..8529b60a854 100644 --- a/LibCarla/source/carla/rpc/Metadata.h +++ b/LibCarla/source/carla/rpc/Metadata.h @@ -37,7 +37,7 @@ namespace rpc { public: - MSGPACK_DEFINE_ARRAY(_asynchronous_call); + MSGPACK_DEFINE_ARRAY(_asynchronous_call) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/ObjectLabel.h b/LibCarla/source/carla/rpc/ObjectLabel.h index 1f51a550a19..6a95338fd32 100644 --- a/LibCarla/source/carla/rpc/ObjectLabel.h +++ b/LibCarla/source/carla/rpc/ObjectLabel.h @@ -9,6 +9,7 @@ #include "carla/MsgPack.h" #include +#include namespace carla { namespace rpc { @@ -52,4 +53,43 @@ namespace rpc { } // namespace rpc } // namespace carla -MSGPACK_ADD_ENUM(carla::rpc::CityObjectLabel); +MSGPACK_ADD_ENUM(carla::rpc::CityObjectLabel) + +namespace std { + inline std::string to_string(carla::rpc::CityObjectLabel label) { + switch (label) + { + case carla::rpc::CityObjectLabel::None: return "None"; + case carla::rpc::CityObjectLabel::Roads: return "Roads"; + case carla::rpc::CityObjectLabel::Sidewalks: return "Sidewalks"; + case carla::rpc::CityObjectLabel::Buildings: return "Buildings"; + case carla::rpc::CityObjectLabel::Walls: return "Walls"; + case carla::rpc::CityObjectLabel::Fences: return "Fences"; + case carla::rpc::CityObjectLabel::Poles: return "Poles"; + case carla::rpc::CityObjectLabel::TrafficLight: return "TrafficLight"; + case carla::rpc::CityObjectLabel::TrafficSigns: return "TrafficSigns"; + case carla::rpc::CityObjectLabel::Vegetation: return "Vegetation"; + case carla::rpc::CityObjectLabel::Terrain: return "Terrain"; + case carla::rpc::CityObjectLabel::Sky: return "Sky"; + case carla::rpc::CityObjectLabel::Pedestrians: return "Pedestrians"; + case carla::rpc::CityObjectLabel::Rider: return "Rider"; + case carla::rpc::CityObjectLabel::Car: return "Car"; + case carla::rpc::CityObjectLabel::Truck: return "Truck"; + case carla::rpc::CityObjectLabel::Bus: return "Bus"; + case carla::rpc::CityObjectLabel::Train: return "Train"; + case carla::rpc::CityObjectLabel::Motorcycle: return "Motorcycle"; + case carla::rpc::CityObjectLabel::Bicycle: return "Bicycle"; + case carla::rpc::CityObjectLabel::Static: return "Static"; + case carla::rpc::CityObjectLabel::Dynamic: return "Dynamic"; + case carla::rpc::CityObjectLabel::Other: return "Other"; + case carla::rpc::CityObjectLabel::Water: return "Water"; + case carla::rpc::CityObjectLabel::RoadLines: return "RoadLines"; + case carla::rpc::CityObjectLabel::Ground: return "Ground"; + case carla::rpc::CityObjectLabel::Bridge: return "Bridge"; + case carla::rpc::CityObjectLabel::RailTrack: return "RailTrack"; + case carla::rpc::CityObjectLabel::GuardRail: return "GuardRail"; + case carla::rpc::CityObjectLabel::Any: return "Any"; + default: return "Unknown"; + } + }; +} // namespace std diff --git a/LibCarla/source/carla/rpc/OpendriveGenerationParameters.h b/LibCarla/source/carla/rpc/OpendriveGenerationParameters.h index 56d123a84fd..f322999d24b 100644 --- a/LibCarla/source/carla/rpc/OpendriveGenerationParameters.h +++ b/LibCarla/source/carla/rpc/OpendriveGenerationParameters.h @@ -48,7 +48,7 @@ namespace rpc { additional_width, smooth_junctions, enable_mesh_visibility, - enable_pedestrian_navigation); + enable_pedestrian_navigation) }; } diff --git a/LibCarla/source/carla/rpc/QualityLevel.h b/LibCarla/source/carla/rpc/QualityLevel.h index eb841a47a3f..a1ada748961 100644 --- a/LibCarla/source/carla/rpc/QualityLevel.h +++ b/LibCarla/source/carla/rpc/QualityLevel.h @@ -26,4 +26,4 @@ namespace rpc { } // namespace rpc } // namespace carla -MSGPACK_ADD_ENUM(carla::rpc::QualityLevel); +MSGPACK_ADD_ENUM(carla::rpc::QualityLevel) diff --git a/LibCarla/source/carla/rpc/RpcServerInterface.h b/LibCarla/source/carla/rpc/RpcServerInterface.h index e4be9944755..6c69d4631da 100644 --- a/LibCarla/source/carla/rpc/RpcServerInterface.h +++ b/LibCarla/source/carla/rpc/RpcServerInterface.h @@ -11,12 +11,15 @@ #include "carla/rpc/ActorDescription.h" #include "carla/rpc/AttachmentType.h" #include "carla/rpc/EpisodeSettings.h" +#include "carla/rpc/EnvironmentObject.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/VehicleLightState.h" #include "carla/rpc/VehicleTelemetryData.h" +#include "carla/rpc/WeatherParameters.h" #include "carla/streaming/detail/Dispatcher.h" namespace carla { @@ -65,7 +68,8 @@ class RpcServerInterface { 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; + virtual Response call_get_telemetry_data(ActorId ActorId) = 0; + virtual Response call_get_vehicle_light_state(ActorId ActorId) = 0; /** * @} @@ -75,9 +79,9 @@ class RpcServerInterface { * @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; + virtual Response call_enable_actor_for_ros(ActorId actor_id) = 0; + virtual Response call_disable_actor_for_ros(ActorId actor_id) = 0; + virtual Response call_is_actor_enabled_for_ros(ActorId actor_id) = 0; /** * @} */ @@ -89,7 +93,7 @@ class RpcServerInterface { virtual Response call_tick( synchronization_client_id_type const &client_id, synchronization_participant_id_type const &participant_id, - carla::rpc::SynchronizationTickMode synchronization_tick_mode) = 0; + SynchronizationTickMode synchronization_tick_mode) = 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; @@ -98,10 +102,32 @@ class RpcServerInterface { 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; + virtual Response > > call_get_synchronization_window_status() = 0; /** * @} */ + + /** + * @brief weather related calls + * @{ + */ + virtual Response call_get_weather_parameters() = 0; + virtual Response call_set_weather_parameters(WeatherParameters const &weather_parameters) = 0; + /** + * @} + */ + + /** + * @brief environment objects related calls + * @{ + */ + virtual Response> call_get_environment_objects(uint8_t queried_tag) =0; + virtual Response call_enable_environment_objects( + const std::vector& env_objects_ids, + bool enable) = 0; + /** + * @} + */ }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/Texture.h b/LibCarla/source/carla/rpc/Texture.h index 04b1832b2cf..3967133c03e 100644 --- a/LibCarla/source/carla/rpc/Texture.h +++ b/LibCarla/source/carla/rpc/Texture.h @@ -60,7 +60,7 @@ namespace rpc { public: - MSGPACK_DEFINE_ARRAY(_width, _height, _texture_data); + MSGPACK_DEFINE_ARRAY(_width, _height, _texture_data) }; using TextureColor = Texture; diff --git a/LibCarla/source/carla/rpc/TrafficLightState.h b/LibCarla/source/carla/rpc/TrafficLightState.h index a4ad6a68453..628b045a410 100644 --- a/LibCarla/source/carla/rpc/TrafficLightState.h +++ b/LibCarla/source/carla/rpc/TrafficLightState.h @@ -25,4 +25,4 @@ namespace rpc { } // namespace rpc } // namespace carla -MSGPACK_ADD_ENUM(carla::rpc::TrafficLightState); +MSGPACK_ADD_ENUM(carla::rpc::TrafficLightState) diff --git a/LibCarla/source/carla/rpc/VehicleAckermannControl.h b/LibCarla/source/carla/rpc/VehicleAckermannControl.h index 2d9bdd6327d..59d1b3e9b19 100644 --- a/LibCarla/source/carla/rpc/VehicleAckermannControl.h +++ b/LibCarla/source/carla/rpc/VehicleAckermannControl.h @@ -84,7 +84,7 @@ namespace rpc { speed, acceleration, jerk, - timestamp); + timestamp) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/VehicleControl.h b/LibCarla/source/carla/rpc/VehicleControl.h index d14821e1eb7..241f48a8c12 100644 --- a/LibCarla/source/carla/rpc/VehicleControl.h +++ b/LibCarla/source/carla/rpc/VehicleControl.h @@ -100,7 +100,7 @@ namespace rpc { reverse, manual_gear_shift, gear, - timestamp); + timestamp) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/VehicleDoor.h b/LibCarla/source/carla/rpc/VehicleDoor.h index 59dfa171946..557c7eb055c 100644 --- a/LibCarla/source/carla/rpc/VehicleDoor.h +++ b/LibCarla/source/carla/rpc/VehicleDoor.h @@ -26,4 +26,4 @@ namespace rpc { } // namespace rpc } // namespace carla -MSGPACK_ADD_ENUM(carla::rpc::VehicleDoor); +MSGPACK_ADD_ENUM(carla::rpc::VehicleDoor) diff --git a/LibCarla/source/carla/rpc/VehiclePhysicsControl.h b/LibCarla/source/carla/rpc/VehiclePhysicsControl.h index 9ce118b7731..8891e8b2854 100644 --- a/LibCarla/source/carla/rpc/VehiclePhysicsControl.h +++ b/LibCarla/source/carla/rpc/VehiclePhysicsControl.h @@ -267,7 +267,7 @@ namespace rpc { center_of_mass, steering_curve, wheels, - use_sweep_wheel_collision); + use_sweep_wheel_collision) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/VehicleTelemetryData.h b/LibCarla/source/carla/rpc/VehicleTelemetryData.h index 21e711eebd4..a006345f7dc 100644 --- a/LibCarla/source/carla/rpc/VehicleTelemetryData.h +++ b/LibCarla/source/carla/rpc/VehicleTelemetryData.h @@ -116,7 +116,7 @@ namespace rpc { engine_rpm, gear, drag, - wheels); + wheels) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/VehicleWheels.h b/LibCarla/source/carla/rpc/VehicleWheels.h index 6e0f5aeaee9..2cba2bd18ab 100644 --- a/LibCarla/source/carla/rpc/VehicleWheels.h +++ b/LibCarla/source/carla/rpc/VehicleWheels.h @@ -26,4 +26,4 @@ namespace rpc { } } -MSGPACK_ADD_ENUM(carla::rpc::VehicleWheelLocation); +MSGPACK_ADD_ENUM(carla::rpc::VehicleWheelLocation) diff --git a/LibCarla/source/carla/rpc/WalkerBoneControlIn.h b/LibCarla/source/carla/rpc/WalkerBoneControlIn.h index ed1a7732f56..d2c5c941a5b 100644 --- a/LibCarla/source/carla/rpc/WalkerBoneControlIn.h +++ b/LibCarla/source/carla/rpc/WalkerBoneControlIn.h @@ -45,7 +45,7 @@ namespace rpc { std::vector bone_transforms; - MSGPACK_DEFINE_ARRAY(bone_transforms); + MSGPACK_DEFINE_ARRAY(bone_transforms) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/WalkerBoneControlOut.h b/LibCarla/source/carla/rpc/WalkerBoneControlOut.h index 745bc732e48..4f9681b77ee 100644 --- a/LibCarla/source/carla/rpc/WalkerBoneControlOut.h +++ b/LibCarla/source/carla/rpc/WalkerBoneControlOut.h @@ -33,7 +33,7 @@ namespace rpc { std::vector bone_transforms; - MSGPACK_DEFINE_ARRAY(bone_transforms); + MSGPACK_DEFINE_ARRAY(bone_transforms) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/WalkerControl.h b/LibCarla/source/carla/rpc/WalkerControl.h index 65d7d728bb2..c4d8a45bc52 100644 --- a/LibCarla/source/carla/rpc/WalkerControl.h +++ b/LibCarla/source/carla/rpc/WalkerControl.h @@ -68,7 +68,7 @@ namespace rpc { return !(*this != rhs); } - MSGPACK_DEFINE_ARRAY(direction, speed, jump, timestamp); + MSGPACK_DEFINE_ARRAY(direction, speed, jump, timestamp) }; } // namespace rpc diff --git a/LibCarla/source/carla/rpc/WeatherParameters.h b/LibCarla/source/carla/rpc/WeatherParameters.h index b267c0caafe..3009cd4de67 100644 --- a/LibCarla/source/carla/rpc/WeatherParameters.h +++ b/LibCarla/source/carla/rpc/WeatherParameters.h @@ -171,7 +171,7 @@ namespace rpc { scattering_intensity, mie_scattering_scale, rayleigh_scattering_scale, - dust_storm); + dust_storm) }; } // namespace rpc diff --git a/LibCarla/source/carla/sensor/RawData.h b/LibCarla/source/carla/sensor/RawData.h index d9212368e5f..570bd047823 100644 --- a/LibCarla/source/carla/sensor/RawData.h +++ b/LibCarla/source/carla/sensor/RawData.h @@ -14,11 +14,6 @@ #include namespace carla { - -namespace ros2 { - class ROS2; -} - namespace sensor { /// Wrapper around the raw data generated by a sensor plus some useful @@ -95,10 +90,6 @@ namespace sensor { template friend class CompositeSerializer; - #if defined(WITH_ROS2) - friend class carla::ros2::ROS2; - #endif - RawData(Buffer DESERIALIZE_DECL_DATA(buffer)) : _buffer(DESERIALIZE_MOVE_DATA(buffer)) {} #if defined(CARLA_SERVER_BUILD) diff --git a/LibCarla/source/carla/sensor/data/Color.h b/LibCarla/source/carla/sensor/data/Color.h index a8d065b9da5..15901db3cc4 100644 --- a/LibCarla/source/carla/sensor/data/Color.h +++ b/LibCarla/source/carla/sensor/data/Color.h @@ -45,7 +45,7 @@ namespace data { uint8_t g = 0u; uint8_t r = 0u; uint8_t a = 0u; - MSGPACK_DEFINE_ARRAY(r, g, b, a); + MSGPACK_DEFINE_ARRAY(r, g, b, a) }; #pragma pack(pop) @@ -72,7 +72,7 @@ static_assert(sizeof(Color) == sizeof(uint32_t), "Invalid color size!"); float x = 0; float y = 0; - MSGPACK_DEFINE_ARRAY(x, y); + MSGPACK_DEFINE_ARRAY(x, y) }; #pragma pack(pop) diff --git a/LibCarla/source/carla/sensor/data/DVSEventArray.h b/LibCarla/source/carla/sensor/data/DVSEventArray.h index 055f2b0d960..79183e69bb1 100644 --- a/LibCarla/source/carla/sensor/data/DVSEventArray.h +++ b/LibCarla/source/carla/sensor/data/DVSEventArray.h @@ -109,7 +109,7 @@ namespace data { std::vector ToArrayPol() const { std::vector array; for (const auto &event : *this) { - array.push_back(2*static_cast(event.pol) - 1); + array.push_back(static_cast(2*event.pol - 1)); } return array; } diff --git a/LibCarla/source/carla/sensor/data/ImageTmpl.h b/LibCarla/source/carla/sensor/data/ImageTmpl.h index bce0fb00da2..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; 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/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/SemanticLidarData.h b/LibCarla/source/carla/sensor/data/SemanticLidarData.h index 8fa2204bd9d..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 { @@ -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/SerializerVectorAllocator.h b/LibCarla/source/carla/sensor/data/SerializerVectorAllocator.h new file mode 100644 index 00000000000..e942f20145b --- /dev/null +++ b/LibCarla/source/carla/sensor/data/SerializerVectorAllocator.h @@ -0,0 +1,160 @@ +// 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/Exception.h" +#include "carla/Logging.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) { + log_verbose("SerializerVectorAllocator[", this, ":", _buffer?static_cast(_buffer->data()):nullptr, "|", _buffer.use_count(), "] created"); + } + + SerializerVectorAllocator(SerializerVectorAllocator &&other) : + std::allocator(), + _buffer(std::move(other._buffer)), + _header_offset(std::exchange(other._header_offset, 0u)), + _is_allocated(std::exchange(other._is_allocated, false)) { + log_verbose("SerializerVectorAllocator[", this, ":", _buffer?static_cast(_buffer->data()):nullptr, "|", _buffer.use_count(),"] created by move from [", &other, "]"); + } + + SerializerVectorAllocator(const SerializerVectorAllocator &other) : + std::allocator(), + _buffer(other._buffer), + _header_offset(other._header_offset), + _is_allocated(other._is_allocated) { + log_verbose("SerializerVectorAllocator[", this, ":", _buffer?static_cast(_buffer->data()):nullptr, "|", _buffer.use_count(),"] created by copy from [", &other, "]"); + } + + ~SerializerVectorAllocator() { + log_verbose("~SerializerVectorAllocator[", this, ":", _buffer?static_cast(_buffer->data()):nullptr, "|", _buffer.use_count(),"] destroyed"); + } + + SerializerVectorAllocator& operator=(SerializerVectorAllocator &&other) { + log_verbose("SerializerVectorAllocator[", this, ":", _buffer?static_cast(_buffer->data()):nullptr, "|", _buffer.use_count(),"] move assigned from [", &other, "]"); + _buffer = std::move(other._buffer); + _header_offset = std::exchange(other._header_offset, 0u); + _is_allocated = std::exchange(other._is_allocated, false); + return *this; + } + + SerializerVectorAllocator& operator=(const SerializerVectorAllocator &other) { + log_verbose("SerializerVectorAllocator[", this, ":", _buffer?static_cast(_buffer->data()):nullptr, "|", _buffer.use_count(),"] assigned from [", &other, "]"); + _buffer = other._buffer; + _header_offset = other._header_offset; + return *this; + } + + 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, + 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/s11n/LidarSerializer.h b/LibCarla/source/carla/sensor/s11n/LidarSerializer.h index 87321961e74..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; @@ -54,6 +60,7 @@ namespace s11n { private: friend class LidarSerializer; + friend class carla::ros2::UePublisherBasePointCloud; explicit LidarHeaderView(const uint32_t *begin) : _begin(begin) { DEBUG_ASSERT(_begin != nullptr); diff --git a/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.h b/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.h index f31a46d4f20..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; @@ -55,6 +61,7 @@ namespace s11n { protected: friend class SemanticLidarSerializer; + friend class carla::ros2::UePublisherBasePointCloud; explicit SemanticLidarHeaderView(const uint32_t *begin) : _begin(begin) { DEBUG_ASSERT(_begin != nullptr); diff --git a/LibCarla/source/carla/streaming/Server.h b/LibCarla/source/carla/streaming/Server.h index f3a17cd221e..5b02e181c4f 100644 --- a/LibCarla/source/carla/streaming/Server.h +++ b/LibCarla/source/carla/streaming/Server.h @@ -75,8 +75,8 @@ namespace streaming { return _server.GetToken(sensor_id); } - void SetROS2TopicVisibilityDefaultEnabled(bool _topic_visibility_default_enabled) { - _server.SetROS2TopicVisibilityDefaultEnabled(_topic_visibility_default_enabled); + void SetROS2TopicVisibilityDefaultEnabled(bool topic_visibility_default_enabled) { + _server.SetROS2TopicVisibilityDefaultEnabled(topic_visibility_default_enabled); } void EnableForROS(detail::stream_actor_id_type stream_actor_id) { diff --git a/LibCarla/source/carla/streaming/Token.h b/LibCarla/source/carla/streaming/Token.h index 7c4937d3503..dda52592ca3 100644 --- a/LibCarla/source/carla/streaming/Token.h +++ b/LibCarla/source/carla/streaming/Token.h @@ -19,7 +19,7 @@ namespace streaming { std::array data; - MSGPACK_DEFINE_ARRAY(data); + MSGPACK_DEFINE_ARRAY(data) }; } // namespace streaming diff --git a/LibCarla/source/carla/streaming/detail/Message.h b/LibCarla/source/carla/streaming/detail/Message.h index 245cca7f9a5..f03ecc8e1a5 100644 --- a/LibCarla/source/carla/streaming/detail/Message.h +++ b/LibCarla/source/carla/streaming/detail/Message.h @@ -20,6 +20,7 @@ #include #include #include +#include namespace carla { namespace streaming { @@ -59,6 +60,11 @@ namespace detail { : MessageTmpl(sizeof...(Buffers) + 1u, buf, buffers...) { static_assert(sizeof...(Buffers) < max_size(), "Too many buffers!"); _buffer_views[0u] = boost::asio::buffer(&_total_size, sizeof(_total_size)); + log_verbose("MessageTmpl[", this, "] Created message with ", _number_of_buffers, " buffers and total size ", _total_size, " bytes. ", GetBufferDetailsAsString()); + } + + ~MessageTmpl(){ + log_verbose("MessageTmpl[", this, "] Destroyed.", GetBufferDetailsAsString()); } /// Size in bytes of the message excluding the header. @@ -79,6 +85,14 @@ namespace detail { auto begin = _buffers.begin(); return MakeListView(begin, begin + _number_of_buffers); } + + auto GetBufferDetailsAsString() const { + std::stringstream result; + for (size_t i = 0; i < _number_of_buffers; ++i) { + result << " Buffer[" << i << "|" << static_cast(_buffers[i]->data()) << "]: size=" << _buffers[i]->size() << " bytes | use_count= " << _buffers[i].use_count(); + } + return result.str(); + } private: message_size_type _number_of_buffers = 0u; diff --git a/LibCarla/source/carla/streaming/detail/MultiStreamState.h b/LibCarla/source/carla/streaming/detail/MultiStreamState.h index a91e642d2f3..da3b1d61242 100644 --- a/LibCarla/source/carla/streaming/detail/MultiStreamState.h +++ b/LibCarla/source/carla/streaming/detail/MultiStreamState.h @@ -36,7 +36,7 @@ namespace detail { if (session != nullptr) { auto message = Session::MakeMessage(buffers...); session->WriteMessage(std::move(message)); - log_debug("sensor ", session->get_stream_id(), " data sent"); + log_verbose("MultiStreamState::Write>> sensor ", session->get_stream_id(), " data sent to single session"); // Return here, _session is only valid if we have a // single session. return; @@ -49,9 +49,10 @@ namespace detail { for (auto &s : _sessions) { if (s != nullptr) { s->WriteMessage(message); - log_debug("sensor ", s->get_stream_id(), " data sent "); + log_verbose("MultiStreamState::Write>> sensor ", s->get_stream_id(), " data sent to session ", message->GetBufferDetailsAsString()); } } + log_verbose("MultiStreamState::Write>> Write finished for multiple sessions"); } } diff --git a/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp b/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp index a4545690ee7..bcb36fcdff7 100644 --- a/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp +++ b/LibCarla/source/carla/streaming/detail/tcp/ServerSession.cpp @@ -103,12 +103,12 @@ namespace tcp { log_info("session", _session_id, ": error sending data :", ec.message()); CloseNow(ec); } else { - DEBUG_ONLY(log_debug("session", _session_id, ": successfully sent", bytes, "bytes")); + DEBUG_ONLY(log_debug("session", _session_id, ": successfully sent", bytes, "bytes ", message->GetBufferDetailsAsString())); DEBUG_ASSERT_EQ(bytes, sizeof(message_size_type) + message->size()); } }; - log_debug("session", _session_id, ": sending message of", message->size(), "bytes"); + log_verbose("session", _session_id, ": sending message of", message->size(), "bytes ", message->GetBufferDetailsAsString()); _deadline.expires_from_now(_timeout); boost::asio::async_write(_socket, message->GetBufferSequence(), diff --git a/LibCarla/source/carla/streaming/low_level/Server.h b/LibCarla/source/carla/streaming/low_level/Server.h index 3d7948c0a94..9b294b048fe 100644 --- a/LibCarla/source/carla/streaming/low_level/Server.h +++ b/LibCarla/source/carla/streaming/low_level/Server.h @@ -81,8 +81,8 @@ namespace low_level { return _dispatcher->GetToken(stream_id); } - void SetROS2TopicVisibilityDefaultEnabled(bool _topic_visibility_default_enabled) { - _dispatcher->SetROS2TopicVisibilityDefaultEnabled(_topic_visibility_default_enabled); + void SetROS2TopicVisibilityDefaultEnabled(bool topic_visibility_default_enabled) { + _dispatcher->SetROS2TopicVisibilityDefaultEnabled(topic_visibility_default_enabled); } void EnableForROS(detail::stream_actor_id_type stream_actor_id) { diff --git a/PythonAPI/carla/setup.py b/PythonAPI/carla/setup.py index c4eddd9fd61..a65935279cd 100755 --- a/PythonAPI/carla/setup.py +++ b/PythonAPI/carla/setup.py @@ -59,15 +59,14 @@ 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', - '-Wduplicate-enum', '-Wnon-virtual-dtor', '-Wheader-hygiene', - '-Wconversion', '-Wfloat-overflow-conversion', - '-Wno-error=unused-command-line-argument', - '-DBOOST_ERROR_CODE_HEADER_ONLY', '-DLIBCARLA_WITH_PYTHON_SUPPORT', - '-stdlib=libstdc++' + '-Wnon-virtual-dtor', + '-Wconversion', + '-Wno-error=null-dereference', '-Wno-error=maybe-uninitialized', + '-DBOOST_ERROR_CODE_HEADER_ONLY', '-DLIBCARLA_WITH_PYTHON_SUPPORT' ] if is_rss_variant_enabled(): extra_compile_args += ['-DLIBCARLA_RSS_ENABLED'] diff --git a/Unreal/CarlaUE4/Config/DefaultGame.ini b/Unreal/CarlaUE4/Config/DefaultGame.ini index 228cab74957..635adea085a 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 diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp index 2cc4821ea01..9760c99a667 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorDispatcher.cpp @@ -8,17 +8,45 @@ #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/HSSLidar.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 +200,151 @@ 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 and AHSSLidar, 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::HSSLidar; + } 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()); + auto *SceneCaptureCamera = 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 if (SceneCaptureCamera != nullptr) { + // scene capture cameras are allowed to be moved by external user + carla::ros2::types::ActorSetTransformCallback ActorSetTransformCallback = [Sensor](carla::ros2::types::Transform &Transform) -> void { + Sensor->SetActorTransform(Transform.GetTransform()); + }; + ROS2->AddSensorUe(SensorActorDefinition, ActorSetTransformCallback); + } + else { + ROS2->AddSensorUe(SensorActorDefinition); + } + } + else if (Vehicle != nullptr ) { + FVehiclePhysicsControl PhysicsControl; + CarlaActor->GetPhysicsControl(PhysicsControl); + ActorNameDefinition.city_object_label = static_cast(ATagger::GetTagOfTaggedComponent(*Vehicle->GetMesh())); + auto VehicleActorDefinition = std::make_shared( + ActorNameDefinition, + CarlaActor->GetActorInfo()->BoundingBox, + PhysicsControl); + + 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 &Transform) -> void { + Vehicle->SetActorTransform(Transform.GetTransform()); + }; + + ROS2->AddVehicleUe(VehicleActorDefinition, VehicleControlCallback, VehicleAckermannControlCallback, VehicleSetTransformCallback); + } + else if ( Walker != nullptr ) { + ActorNameDefinition.city_object_label = carla::rpc::CityObjectLabel::Pedestrians; + auto WalkerActorDefinition = std::make_shared( + ActorNameDefinition, + CarlaActor->GetActorInfo()->BoundingBox); + + 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 ) { + ActorNameDefinition.city_object_label = carla::rpc::CityObjectLabel::TrafficLight; + auto TrafficLightTriggerVolume = UBoundingBoxCalculator::GetTrafficSignTriggerVolume(TrafficLight); + auto TrafficLightActorDefinition = std::make_shared( + ActorNameDefinition, + CarlaActor->GetActorInfo()->BoundingBox, + TrafficLightTriggerVolume); + ROS2->AddTrafficLightUe(TrafficLightActorDefinition); + } + else if ( TrafficSign != nullptr ) { + ActorNameDefinition.city_object_label = carla::rpc::CityObjectLabel::TrafficSigns; + auto TrafficSignActorDefinition = std::make_shared( + ActorNameDefinition, + CarlaActor->GetActorInfo()->BoundingBox); + ROS2->AddTrafficSignUe(TrafficSignActorDefinition); + } +} +#endif + FCarlaActor* UActorDispatcher::RegisterActor( AActor &Actor, FActorDescription Description, FActorRegistry::IdType DesiredId) @@ -186,40 +359,12 @@ 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()); - } - - 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; - } - - 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)), + Description, + ROS2->VisibilityDefaultMode()); + RegisterActorROS2(ROS2, View, ActorNameDefinition); } #endif } @@ -241,27 +386,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/Carla.Build.cs b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs index 3fc6b7fa333..5a91270d08d 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Carla.Build.cs @@ -199,10 +199,18 @@ private void AddCarlaServerDependency(ReadOnlyTargetRules Target) if (UseDebugLibs(Target)) { PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_server_debug"))); + if (UsingRos2) + { + PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_fastdds_debug"))); + } } else { PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_server"))); + if (UsingRos2) + { + PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_fastdds"))); + } } if (UsingChrono) { @@ -230,10 +238,18 @@ private void AddCarlaServerDependency(ReadOnlyTargetRules Target) if (UseDebugLibs(Target)) { PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_server_debug"))); + if (UsingRos2) + { + PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_fastdds_debug"))); + } } else { PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_server"))); + if (UsingRos2) + { + PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", GetLibName("carla_fastdds"))); + } } if (UsingChrono) { @@ -318,11 +334,8 @@ private void AddCarlaServerDependency(ReadOnlyTargetRules Target) PublicAdditionalLibraries.Add("stdc++"); PublicAdditionalLibraries.Add("/usr/lib/x86_64-linux-gnu/libpython3.9.so"); } - 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 +358,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 738b5372473..c8ab8e17c32 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; @@ -215,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::ROS2TopicVisibilityDefaultMode::eOn:carla::ros2::ROS2TopicVisibilityDefaultMode::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) @@ -262,29 +286,55 @@ 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) { // process RPC commands do { Server.RunSome(1u); + #if defined(WITH_ROS2) + if (ROS2->IsEnabled()) + { + ROS2->ProcessMessages(); + } + #endif } while (Server.IsSynchronousModeActive() && !Server.TickCueReceived()); @@ -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 } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEngine.h index 24638f98956..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() diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.cpp index 84fbc1a3d6a..c8620ca8e9e 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( diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaEpisode.h index 7fd78e9ef33..f0e2807d5d2 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 @@ -362,11 +361,6 @@ class CARLA_API UCarlaEpisode : public UObject { ElapsedGameTime += DeltaSeconds; SetVisualGameTime(VisualGameTime + DeltaSeconds); - #if defined(WITH_ROS2) - auto ROS2 = carla::ros2::ROS2::GetInstance(); - if (ROS2->IsEnabled()) - ROS2->SetTimestamp(GetElapsedGameTime()); - #endif } 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/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..148d27d346e 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/PixelReader.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/PixelReader.h @@ -136,9 +136,6 @@ void FPixelReader::SendPixelsInRenderThread(TSensor &Sensor, bool use16BitFormat } auto Stream = Sensor.GetDataStream(Sensor); - Stream.SetFrameNumber(Frame); - Stream.SetTimestamp(Timestamp); - Stream.SetTransform(Transform); auto Buffer = Stream.PopBufferFromPool(); uint32 CurrentRowBytes = ExpectedRowBytes; @@ -179,30 +176,25 @@ void FPixelReader::SendPixelsInRenderThread(TSensor &Sensor, bool use16BitFormat TRACE_CPUPROFILER_EVENT_SCOPE_STR("Sending buffer"); if(Buffer.data()) { - // serialize data - 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()) + // Move the buffer and necessary context into a background task + // We want to exit the rendering thread as soon as possible to ensure the locks on the + // hardware buffers are released + AsyncTask(ENamedThreads::AnyBackgroundHiPriTask, [Buffer = std::move(Buffer), &Sensor, Frame, Timestamp, Transform]() mutable { - 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"); - Stream.Send(Sensor, BufView); + TRACE_CPUPROFILER_EVENT_SCOPE_STR("Async Network Send"); + + // since we are again in another thread, re-check for sensor destruction + if (Sensor.IsPendingKill()) return; + + carla::Buffer BufferReady(std::move(carla::sensor::SensorRegistry::Serialize(Sensor, std::move(Buffer)))); + carla::SharedBufferView BufView = carla::BufferView::CreateFrom(std::move(BufferReady)); + + auto Stream = Sensor.GetDataStream(Sensor); + Stream.SetFrameNumber(Frame); + Stream.SetTimestamp(Timestamp); + Stream.SetTransform(Transform); + Stream.Send(Sensor, BufView); + }); } } }; 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/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index e64e00cfe10..1fecd105c36 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -201,6 +201,7 @@ class FCarlaServer::FPimpl: public carla::rpc::RpcServerInterface 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; + carla::rpc::Response call_get_vehicle_light_state(carla::rpc::ActorId ActorId) override; /** * @} */ @@ -253,6 +254,29 @@ class FCarlaServer::FPimpl: public carla::rpc::RpcServerInterface /** * @} */ + + /** + * @brief weather related calls + * @{ + */ + carla::rpc::Response call_get_weather_parameters() override; + carla::rpc::Response call_set_weather_parameters(carla::rpc::WeatherParameters const &weather_parameters) override; + /** + * @} + */ + + /** + * @brief environment objects related calls + * @{ + */ + carla::rpc::Response> call_get_environment_objects(uint8_t queried_tag) override; + carla::rpc::Response call_enable_environment_objects( + const std::vector& env_objects_ids, + bool enable) override; + /** + * @} + */ + void OnClientDisconnected(std::shared_ptr server_session); void OnClientConnected(std::shared_ptr server_session); bool IsNextGameTickAllowed(); @@ -827,40 +851,13 @@ void FCarlaServer::FPimpl::BindActions() BIND_SYNC(get_environment_objects) << [this](uint8 QueriedTag) -> R> { REQUIRE_CARLA_EPISODE(); - ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld()); - if (!GameMode) - { - RESPOND_ERROR("unable to find CARLA game mode"); - } - TArray Result = GameMode->GetEnvironmentObjects(QueriedTag); - ALargeMapManager* LargeMap = GameMode->GetLMManager(); - if (LargeMap) - { - for(auto& Object : Result) - { - Object.Transform = LargeMap->LocalToGlobalTransform(Object.Transform); - } - } - return MakeVectorFromTArray(Result); + return call_get_environment_objects(QueriedTag); }; BIND_SYNC(enable_environment_objects) << [this](std::vector EnvObjectIds, bool Enable) -> R { REQUIRE_CARLA_EPISODE(); - ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld()); - if (!GameMode) - { - RESPOND_ERROR("unable to find CARLA game mode"); - } - - TSet EnvObjectIdsSet; - for(uint64 Id : EnvObjectIds) - { - EnvObjectIdsSet.Emplace(Id); - } - - GameMode->EnableEnvironmentObjects(EnvObjectIdsSet, Enable); - return R::Success(); + return call_enable_environment_objects(EnvObjectIds, Enable); }; BIND_SYNC(set_annotations_traverse_translucency) << [this](bool Enable) -> R @@ -875,25 +872,14 @@ void FCarlaServer::FPimpl::BindActions() BIND_SYNC(get_weather_parameters) << [this]() -> R { REQUIRE_CARLA_EPISODE(); - auto *Weather = Episode->GetWeather(); - if (Weather == nullptr) - { - RESPOND_ERROR("internal error: unable to find weather"); - } - return Weather->GetCurrentWeather(); + return call_get_weather_parameters(); }; BIND_SYNC(set_weather_parameters) << [this]( const cr::WeatherParameters &weather) -> R { REQUIRE_CARLA_EPISODE(); - auto *Weather = Episode->GetWeather(); - if (Weather == nullptr) - { - RESPOND_ERROR("internal error: unable to find weather"); - } - Weather->ApplyWeather(weather); - return R::Success(); + return call_set_weather_parameters(weather); }; // -- IMUI Gravity --------------------------------------------------------- @@ -1865,25 +1851,7 @@ BIND_SYNC(send) << [this]( cr::ActorId ActorId) -> R { REQUIRE_CARLA_EPISODE(); - FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); - if (!CarlaActor) - { - return RespondError( - "get_vehicle_light_state", - ECarlaServerResponse::ActorNotFound, - " Actor Id: " + FString::FromInt(ActorId)); - } - FVehicleLightState LightState; - ECarlaServerResponse Response = - CarlaActor->GetVehicleLightState(LightState); - if (Response != ECarlaServerResponse::Success) - { - return RespondError( - "get_vehicle_light_state", - Response, - " Actor Id: " + FString::FromInt(ActorId)); - } - return cr::VehicleLightState(LightState); + return call_get_vehicle_light_state(ActorId); }; BIND_SYNC(apply_physics_control) << [this]( @@ -3467,26 +3435,6 @@ carla::rpc::Response FCarlaServer::FPimpl::call_spawn_actor_w 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()) @@ -3604,6 +3552,29 @@ carla::rpc::Response FCarlaServer::FPimpl::cal return carla::rpc::VehicleTelemetryData(TelemetryData); } +carla::rpc::Response FCarlaServer::FPimpl::call_get_vehicle_light_state(carla::rpc::ActorId ActorId) +{ + FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId); + if (!CarlaActor) + { + return RespondError( + "get_vehicle_light_state", + ECarlaServerResponse::ActorNotFound, + " Actor Id: " + FString::FromInt(ActorId)); + } + FVehicleLightState LightState; + ECarlaServerResponse Response = + CarlaActor->GetVehicleLightState(LightState); + if (Response != ECarlaServerResponse::Success) + { + return RespondError( + "get_vehicle_light_state", + Response, + " Actor Id: " + FString::FromInt(ActorId)); + } + return carla::rpc::VehicleLightState(LightState); +} + FCarlaServer::FPimpl::CheckHandleActorInSecondaryServerResult FCarlaServer::FPimpl::CheckHandleSensorInSecondaryServer(carla::streaming::detail::stream_id_type stream_id) { FCarlaActor* CarlaActor = Episode->FindCarlaActorByStreamId(stream_id); if ( CarlaActor == nullptr ) @@ -3714,6 +3685,66 @@ carla::rpc::Response FCarlaServer::FPimpl::call_get_weather_parameters() +{ + auto *Weather = Episode->GetWeather(); + if (Weather == nullptr) + { + RESPOND_ERROR("internal error: unable to find weather"); + } + return Weather->GetCurrentWeather(); +} + +carla::rpc::Response FCarlaServer::FPimpl::call_set_weather_parameters(carla::rpc::WeatherParameters const &weather_parameters) +{ + auto *Weather = Episode->GetWeather(); + if (Weather == nullptr) + { + RESPOND_ERROR("internal error: unable to find weather"); + } + Weather->ApplyWeather(weather_parameters); + return R::Success(); +} + +carla::rpc::Response> FCarlaServer::FPimpl::call_get_environment_objects(uint8_t QueriedTag) +{ + ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld()); + if (!GameMode) + { + RESPOND_ERROR("unable to find CARLA game mode"); + } + TArray Result = GameMode->GetEnvironmentObjects(QueriedTag); + ALargeMapManager* LargeMap = GameMode->GetLMManager(); + if (LargeMap) + { + for(auto& Object : Result) + { + Object.Transform = LargeMap->LocalToGlobalTransform(Object.Transform); + } + } + return MakeVectorFromTArray(Result); +} + +carla::rpc::Response FCarlaServer::FPimpl::call_enable_environment_objects( + const std::vector& EnvObjectIds, + bool Enable) +{ + ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld()); + if (!GameMode) + { + RESPOND_ERROR("unable to find CARLA game mode"); + } + + TSet EnvObjectIdsSet; + for(uint64 Id : EnvObjectIds) + { + EnvObjectIdsSet.Emplace(Id); + } + + GameMode->EnableEnvironmentObjects(EnvObjectIdsSet, Enable); + return R::Success(); +} + void FCarlaServer::FPimpl::OnClientConnected(std::shared_ptr server_session) { auto const RegisterResponse = ServerSync.RegisterSynchronizationParticipant(SynchronizationClientId()); if ( RegisterResponse ) { @@ -3868,9 +3899,8 @@ void FCarlaServer::RunSome(uint32 Milliseconds) Pimpl->Server.SyncRunFor(carla::time_duration::milliseconds(Milliseconds)); } - -void FCarlaServer::SetROS2TopicVisibilityDefaultEnabled(bool _topic_visibility_default_enabled) { - Pimpl->StreamingServer.SetROS2TopicVisibilityDefaultEnabled(_topic_visibility_default_enabled); +void FCarlaServer::SetROS2TopicVisibilityDefaultEnabled(bool topic_visibility_default_enabled) { + Pimpl->StreamingServer.SetROS2TopicVisibilityDefaultEnabled(topic_visibility_default_enabled); } void FCarlaServer::EnableSynchronousMode() { @@ -4001,6 +4031,11 @@ carla::rpc::Response FCarlaServer::call_get_te return Pimpl->call_get_telemetry_data(ActorId); } +carla::rpc::Response FCarlaServer::call_get_vehicle_light_state(carla::rpc::ActorId ActorId) +{ + return Pimpl->call_get_vehicle_light_state(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, @@ -4035,3 +4070,24 @@ carla::rpc::Responsecall_get_synchronization_window_status(); } +carla::rpc::Response FCarlaServer::call_get_weather_parameters() +{ + return Pimpl->call_get_weather_parameters(); +} + +carla::rpc::Response FCarlaServer::call_set_weather_parameters(carla::rpc::WeatherParameters const &weather_parameters) +{ + return Pimpl->call_set_weather_parameters(weather_parameters); +} + +carla::rpc::Response> FCarlaServer::call_get_environment_objects(uint8_t QueriedTag) +{ + return Pimpl->call_get_environment_objects(QueriedTag); +} + +carla::rpc::Response FCarlaServer::call_enable_environment_objects( + const std::vector& EnvObjectIds, + bool Enable) +{ + return Pimpl->call_enable_environment_objects(EnvObjectIds, Enable); +} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.h index 9e9d0328443..7a84424a9e1 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.h @@ -42,7 +42,7 @@ class FCarlaServer: public carla::rpc::RpcServerInterface void RunSome(uint32 Milliseconds); - void SetROS2TopicVisibilityDefaultEnabled(bool _topic_visibility_default_enabled); + void SetROS2TopicVisibilityDefaultEnabled(bool topic_visibility_default_enabled); void EnableSynchronousMode(); void DisableSynchronousMode(); @@ -103,6 +103,7 @@ class FCarlaServer: public carla::rpc::RpcServerInterface 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; + carla::rpc::Response call_get_vehicle_light_state(carla::rpc::ActorId ActorId) override; /** * @} */ @@ -138,6 +139,28 @@ class FCarlaServer: public carla::rpc::RpcServerInterface /** * @} */ + + /** + * @brief weather related calls + * @{ + */ + carla::rpc::Response call_get_weather_parameters() override; + carla::rpc::Response call_set_weather_parameters(carla::rpc::WeatherParameters const &weather_parameters) override; + /** + * @} + */ + + /** + * @brief environment objects related calls + * @{ + */ + carla::rpc::Response> call_get_environment_objects(uint8_t queried_tag) override; + carla::rpc::Response call_enable_environment_objects( + const std::vector& env_objects_ids, + bool enable) override; + /** + * @} + */ private: class FPimpl; diff --git a/Util/BuildTools/Ad-rss.sh b/Util/BuildTools/Ad-rss.sh index 01ac4ddf511..b38fb8e2595 100755 --- a/Util/BuildTools/Ad-rss.sh +++ b/Util/BuildTools/Ad-rss.sh @@ -120,7 +120,7 @@ for PY_VERSION in ${PY_VERSION_LIST[@]} ; do echo "PYTHON_BINDING_VERSIONS=${PYTHON_BINDING_VERSIONS}" # enforce sequential executor to reduce the required memory for compilation - colcon build --executor sequential --packages-up-to ad_rss_map_integration --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_TOOLCHAIN_FILE="${CARLA_BUILD_FOLDER}/LibStdCppToolChain.cmake" -DCMAKE_PREFIX_PATH="${CMAKE_PREFIX_PATH}" -DPYTHON_BINDING_VERSIONS="${PYTHON_BINDING_VERSIONS}" --build-base ${ADRSS_BUILD_DIR} --install-base ${ADRSS_INSTALL_DIR} + colcon build --executor sequential --packages-up-to ad_rss_map_integration --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_TOOLCHAIN_FILE="${CARLA_BUILD_FOLDER}/CarlaClientToolChain.cmake" -DCMAKE_PREFIX_PATH="${CMAKE_PREFIX_PATH}" -DPYTHON_BINDING_VERSIONS="${PYTHON_BINDING_VERSIONS}" --build-base ${ADRSS_BUILD_DIR} --install-base ${ADRSS_INSTALL_DIR} COLCON_RESULT=$? if (( COLCON_RESULT )); then diff --git a/Util/BuildTools/BuildLibCarla.sh b/Util/BuildTools/BuildLibCarla.sh index bec6a9be5e7..3ff4cdb7277 100755 --- a/Util/BuildTools/BuildLibCarla.sh +++ b/Util/BuildTools/BuildLibCarla.sh @@ -112,7 +112,7 @@ 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 @@ -130,24 +130,24 @@ function build_libcarla { CMAKE_EXTRA_OPTIONS='' if [ $1 == Server ] ; then - M_TOOLCHAIN=${LIBCPP_TOOLCHAIN_FILE} + M_TOOLCHAIN=${CARLA_SERVER_TOOLCHAIN_FILE} M_BUILD_FOLDER=${LIBCARLA_BUILD_SERVER_FOLDER}.$(echo "$2" | tr '[:upper:]' '[:lower:]') M_INSTALL_FOLDER=${LIBCARLA_INSTALL_SERVER_FOLDER} elif [ $1 == Client ] ; then - M_TOOLCHAIN=${LIBSTDCPP_TOOLCHAIN_FILE} + M_TOOLCHAIN=${CARLA_CLIENT_TOOLCHAIN_FILE} M_BUILD_FOLDER=${LIBCARLA_BUILD_CLIENT_FOLDER}.$(echo "$2" | tr '[:upper:]' '[:lower:]') M_INSTALL_FOLDER=${LIBCARLA_INSTALL_CLIENT_FOLDER} elif [ $1 == Pytorch ] ; then - M_TOOLCHAIN=${LIBSTDCPP_TOOLCHAIN_FILE} + M_TOOLCHAIN=${CARLA_SERVER_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 - M_TOOLCHAIN=${LIBCPP_TOOLCHAIN_FILE} - M_BUILD_FOLDER=${LIBCARLA_FASTDDS_FOLDER}.$(echo "$2" | tr '[:upper:]' '[:lower:]') + M_TOOLCHAIN=${CARLA_SERVER_TOOLCHAIN_FILE} + 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' - M_TOOLCHAIN=${LIBSTDCPP_TOOLCHAIN_FILE} + M_TOOLCHAIN=${CARLA_CLIENT_TOOLCHAIN_FILE} M_BUILD_FOLDER=${LIBCARLA_BUILD_CLIENT_FOLDER}.rss.$(echo "$2" | tr '[:upper:]' '[:lower:]') M_INSTALL_FOLDER=${LIBCARLA_INSTALL_CLIENT_FOLDER} CMAKE_EXTRA_OPTIONS="${CMAKE_EXTRA_OPTIONS:+${CMAKE_EXTRA_OPTIONS} }-DBUILD_RSS_VARIANT=ON -DADRSS_INSTALL_DIR=${CARLA_BUILD_FOLDER}/ad-rss-4.4.4/install" diff --git a/Util/BuildTools/BuildOSM2ODR.sh b/Util/BuildTools/BuildOSM2ODR.sh index 782991e781f..76c14c41425 100755 --- a/Util/BuildTools/BuildOSM2ODR.sh +++ b/Util/BuildTools/BuildOSM2ODR.sh @@ -55,13 +55,15 @@ source $(dirname "$0")/Environment.sh function get_source_code_checksum { local EXCLUDE='*__pycache__*' - find "${OSM2ODR_SOURCE_FOLDER}"/* \! -path "${EXCLUDE}" -print0 | sha1sum | awk '{print $1}' + find "${OSM2ODR_BASENAME}-source"/* \! -path "${EXCLUDE}" -print0 | sha1sum | awk '{print $1}' } if ! { ${REMOVE_INTERMEDIATE} || ${BUILD_OSM2ODR}; }; then fatal_error "Nothing selected to be done." fi +OSM2ODR_BASENAME=${CARLA_BUILD_FOLDER}/osm2odr + # ============================================================================== # -- Clean intermediate files -------------------------------------------------- # ============================================================================== @@ -70,7 +72,8 @@ if ${REMOVE_INTERMEDIATE} ; then log "Cleaning intermediate files and folders." - rm -Rf ${OSM2ODR_BUILD_FOLDER}* + rm -Rf ${OSM2ODR_BASENAME}-client-build* ${OSM2ODR_BASENAME}-server-build* + rm -Rf ${OSM2ODR_BASENAME}-server-install* ${OSM2ODR_BASENAME}-client-install* fi @@ -79,75 +82,66 @@ fi # ============================================================================== if ${BUILD_OSM2ODR} ; then - log "Building OSM2ODR." - if [ ! -d ${OSM2ODR_SOURCE_FOLDER} ] ; then - cd ${CARLA_BUILD_FOLDER} - curl --retry 5 --retry-max-time 120 -L -o OSM2ODR.zip https://github.com/carla-simulator/sumo/archive/${CURRENT_OSM2ODR_COMMIT}.zip - unzip -qq OSM2ODR.zip - rm -f OSM2ODR.zip - mv sumo-${CURRENT_OSM2ODR_COMMIT} ${OSM2ODR_SOURCE_FOLDER} + + if [[ -d ${OSM2ODR_BASENAME}-client-install && -d ${OSM2ODR_BASENAME}-server-install ]] ; then + log "OSM2ODR already installed." + else + rm -Rf \ + ${OSM2ODR_BASENAME}-source \ + ${OSM2ODR_BASENAME}-server-build ${OSM2ODR_BASENAME}-client-build \ + ${OSM2ODR_BASENAME}-server-install ${OSM2ODR_BASENAME}-client-install + + log "Building OSM2ODR." + if [ ! -d ${OSM2ODR_BASENAME}-source ] ; then + cd ${CARLA_BUILD_FOLDER} + curl --retry 5 --retry-max-time 120 -L -o OSM2ODR.zip https://github.com/carla-simulator/sumo/archive/${CURRENT_OSM2ODR_COMMIT}.zip + unzip -qq OSM2ODR.zip + rm -f OSM2ODR.zip + mv sumo-${CURRENT_OSM2ODR_COMMIT} ${OSM2ODR_BASENAME}-source + fi + + mkdir -p ${OSM2ODR_BASENAME}-client-build + pushd ${OSM2ODR_BASENAME}-client-build >/dev/null + + cmake ${OSM2ODR_BASENAME}-source \ + -G "Eclipse CDT4 - Ninja" \ + -DCMAKE_INSTALL_PREFIX=${OSM2ODR_BASENAME}-client-install \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_CLIENT_TOOLCHAIN_FILE}" \ + -DOSM2ODR_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/proj-client-install/include \ + -DOSM2ODR_LIBRARY=${CARLA_BUILD_FOLDER}/proj-client-install/lib/libproj.so \ + -DXercesC_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-client-install/include \ + -DXercesC_LIBRARY=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-client-install/lib/libxerces-c.so + + ninja osm2odr + ninja install + popd >/dev/null + + mkdir -p ${OSM2ODR_BASENAME}-server-build + pushd ${OSM2ODR_BASENAME}-server-build >/dev/null + + cmake ${OSM2ODR_BASENAME}-source \ + -G "Eclipse CDT4 - Ninja" \ + -DCMAKE_INSTALL_PREFIX=${OSM2ODR_BASENAME}-server-install \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_SERVER_TOOLCHAIN_FILE}" \ + -DOSM2ODR_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/proj-server-install/include \ + -DOSM2ODR_LIBRARY=${CARLA_BUILD_FOLDER}/proj-server-install/lib/libproj.a \ + -DXercesC_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-server-install/include \ + -DXercesC_LIBRARY=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-server-install/lib/libxerces-c.a + + ninja osm2odr + ninja install + popd >/dev/null + + rm -Rf ${OSM2ODR_BASENAME}-server-build ${OSM2ODR_BASENAME}-client-build fi - mkdir -p ${OSM2ODR_BUILD_FOLDER} - cd ${OSM2ODR_BUILD_FOLDER} - - - export CC="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin/clang" - export CXX="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin/clang++" - export PATH="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin:$PATH" - - cmake ${OSM2ODR_SOURCE_FOLDER} \ - -G "Eclipse CDT4 - Ninja" \ - -DCMAKE_CXX_FLAGS="-stdlib=libstdc++" \ - -DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_CLIENT_FOLDER} \ - -DPROJ_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/proj-install/include \ - -DPROJ_LIBRARY=${CARLA_BUILD_FOLDER}/proj-install/lib/libproj.a \ - -DXercesC_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install/include \ - -DXercesC_LIBRARY=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install/lib/libxerces-c.a - - ninja osm2odr - ninja install - - mkdir -p ${OSM2ODR_SERVER_BUILD_FOLDER} - cd ${OSM2ODR_SERVER_BUILD_FOLDER} - - LLVM_BASENAME=llvm-8.0 - LLVM_INCLUDE="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/include/c++/v1" - LLVM_LIBPATH="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/lib/Linux/x86_64-unknown-linux-gnu" - - echo $LLVM_INCLUDE - echo $LLVM_LIBPATH - - cmake ${OSM2ODR_SOURCE_FOLDER} \ - -G "Eclipse CDT4 - Ninja" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -L${LLVM_LIBPATH}" \ - -DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_SERVER_FOLDER} \ - -DPROJ_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/proj-install-server/include \ - -DPROJ_LIBRARY=${CARLA_BUILD_FOLDER}/proj-install-server/lib/libproj.a \ - -DXercesC_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install-server/include \ - -DXercesC_LIBRARY=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install-server/lib/libxerces-c.a - - ninja osm2odr - ninja install - - mkdir -p ${OSM2ODR_SERVER_BUILD_FOLDER} - cd ${OSM2ODR_SERVER_BUILD_FOLDER} - - LLVM_BASENAME=llvm-8.0 - LLVM_INCLUDE="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/include/c++/v1" - LLVM_LIBPATH="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/lib/Linux/x86_64-unknown-linux-gnu" - - cmake ${OSM2ODR_SOURCE_FOLDER} \ - -G "Eclipse CDT4 - Ninja" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -L${LLVM_LIBPATH}" \ - -DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_SERVER_FOLDER} \ - -DPROJ_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/proj-install-server/include \ - -DPROJ_LIBRARY=${CARLA_BUILD_FOLDER}/proj-install-server/lib/libproj.a \ - -DXercesC_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install-server/include \ - -DXercesC_LIBRARY=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install-server/lib/libxerces-c.a - - ninja osm2odr - ninja install + mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/include/ ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib + cp -p -r ${OSM2ODR_BASENAME}-server-install/include/* ${LIBCARLA_INSTALL_SERVER_FOLDER}/include/ + cp -p ${OSM2ODR_BASENAME}-server-install/lib/*.a ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib + + mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/include/ ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib + cp -p -r ${OSM2ODR_BASENAME}-client-install/include/* ${LIBCARLA_INSTALL_CLIENT_FOLDER}/include/ + cp -p ${OSM2ODR_BASENAME}-client-install/lib/*.a ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib fi diff --git a/Util/BuildTools/BuildPythonAPI.sh b/Util/BuildTools/BuildPythonAPI.sh index f3b88c87cf5..4fa15edcafd 100755 --- a/Util/BuildTools/BuildPythonAPI.sh +++ b/Util/BuildTools/BuildPythonAPI.sh @@ -55,11 +55,6 @@ while [[ $# -gt 0 ]]; do esac done - -export CC="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin/clang" -export CXX="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin/clang++" -export PATH="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin:$PATH" - source $(dirname "$0")/Environment.sh if ! { ${REMOVE_INTERMEDIATE} || ${BUILD_PYTHONAPI} || ${BUILD_PYTHONAPI_WHEEL} ; }; then @@ -109,7 +104,7 @@ if ${BUILD_PYTHONAPI} ; then if ${INSTALL_PYTHONAPI} ; then log "Installing Python API for Python ${PY_VERSION}." - /usr/bin/env python${PY_VERSION} -m pip install --force-reinstall dist/.tmp/$(ls dist/.tmp | grep .whl) + /usr/bin/env python${PY_VERSION} -m pip install --break-system-packages --force-reinstall dist/.tmp/$(ls dist/.tmp | grep .whl) fi if [[ -z ${TARGET_WHEEL_PLATFORM} ]] ; then 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 26e94088e03..feecd718c17 100755 --- a/Util/BuildTools/Setup.sh +++ b/Util/BuildTools/Setup.sh @@ -52,21 +52,36 @@ done source $(dirname "$0")/Environment.sh -export CC="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin/clang" -export CXX="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin/clang++" -export PATH="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/bin:$PATH" - -CXX_TAG=c10 - # Convert comma-separated string to array of unique elements. IFS="," read -r -a PY_VERSION_LIST <<< "${PY_VERSION_LIST}" mkdir -p ${CARLA_BUILD_FOLDER} pushd ${CARLA_BUILD_FOLDER} >/dev/null -LLVM_INCLUDE="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/include/c++/v1" -LLVM_LIBPATH="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/lib/Linux/x86_64-unknown-linux-gnu" -UNREAL_HOSTED_CFLAGS="--sysroot=$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu/" +# ============================================================================== +# -- Setup Unreal Engine toolchain flags --------------------------------------- +# ============================================================================== +LLVM_INCLUDE="${UE4_ROOT}/Engine/Source/ThirdParty/Linux/LibCxx/include/c++/v1" +LLVM_LIBPATH="${UE4_ROOT}/Engine/Source/ThirdParty/Linux/LibCxx/lib/Linux/x86_64-unknown-linux-gnu" +UNREAL_SYSROOT="$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/HostLinux/Linux_x64/v17_clang-10.0.1-centos7/x86_64-unknown-linux-gnu" +UNREAL_HOSTED_CFLAGS="--sysroot=${UNREAL_SYSROOT} -isystem ${LLVM_INCLUDE}" +UNREAL_SYSTEM_LIBPATH="${UNREAL_SYSROOT}/usr/lib" +UNREAL_HOSTED_LINKER_FLAGS="--sysroot=${UNREAL_SYSROOT} -L${LLVM_LIBPATH} -L${UNREAL_SYSTEM_LIBPATH} -lc++ -lc++abi" + +CARLA_CFLAGS="-fPIC -w" +CARLA_CXXFLAGS="-std=c++17 -DBOOST_ERROR_CODE_HEADER_ONLY" + +CARLA_SERVER_CFLAGS="${UNREAL_HOSTED_CFLAGS} ${CARLA_CFLAGS}" +CARLA_SERVER_CXXFLAGS="${CARLA_SERVER_CFLAGS} ${CARLA_CXXFLAGS} -stdlib=libc++ -DBOOST_NO_EXCEPTIONS -DASIO_NO_EXCEPTIONS" +CARLA_SERVER_LINKER_FLAGS="${UNREAL_HOSTED_LINKER_FLAGS} -L${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/" + +CARLA_SERVER_CC="${UNREAL_SYSROOT}/bin/clang" +CARLA_SERVER_CXX="${UNREAL_SYSROOT}/bin/clang++" +CARLA_CLIENT_CCC="gcc" +CARLA_CLIENT_CXX="g++" + +CLANG_ONLY_WARNINGS="-Wduplicate-enum -Wheader-hygiene -Wfloat-overflow-conversion" + # ============================================================================== # -- Generate CMake toolchains ------------------------------------------------- @@ -74,117 +89,168 @@ UNREAL_HOSTED_CFLAGS="--sysroot=$UE4_ROOT/Engine/Extras/ThirdPartyNotUE/SDKs/Hos log "Generating CMake configuration files." -# -- LIBSTDCPP_TOOLCHAIN_FILE -------------------------------------------------- +# -- CARLA_CLIENT_TOOLCHAIN_FILE -------------------------------------------------- -cat >${LIBSTDCPP_TOOLCHAIN_FILE}.gen <${CARLA_CLIENT_TOOLCHAIN_FILE}.gen <>${CARLA_SERVER_TOOLCHAIN_FILE}.gen <>${LIBCPP_TOOLCHAIN_FILE}.gen <&1) LIB_NAME=$(cut -d . -f 1,2 <<< "$PYTHON_VERSION" | tr -d .) LIB_NAME=${LIB_NAME:7} - if [[ -d "${BOOST_BASENAME}-install" ]] ; then - if [ -f "${BOOST_BASENAME}-install/lib/libboost_python${LIB_NAME}.a" ] ; then - SHOULD_BUILD_BOOST=false - log "${BOOST_BASENAME} already installed." + if [[ -d "${BOOST_BASENAME}-client-install" ]] ; then + if [ -f "${BOOST_BASENAME}-client-install/lib/libboost_python${LIB_NAME}.a" ] ; then + SHOULD_BUILD_BOOST_CLIENT=false + log "${BOOST_BASENAME} already installed for Python ${PY_VERSION}." + fi + fi + if [[ -d "${BOOST_BASENAME}-server-install" ]] ; then + if [ -f "${BOOST_BASENAME}-server-install/lib/libboost_system.a" ] ; then + SHOULD_BUILD_BOOST_SERVER=false fi fi - if { ${SHOULD_BUILD_BOOST} ; } ; then - rm -Rf ${BOOST_BASENAME}-source + if { ${SHOULD_BUILD_BOOST_SERVER} -o ${SHOULD_BUILD_BOOST_CLIENT}; } ; then + # Download boost if required + if [ ! -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ]; then + log "Retrieving boost." - BOOST_PACKAGE_BASENAME=boost_${BOOST_VERSION//./_} + start=$(date +%s) + wget "https://archives.boost.io/release/${BOOST_VERSION}/source/${BOOST_PACKAGE_BASENAME}.tar.gz" -O ${BOOST_PACKAGE_BASENAME}.tar.gz || true + end=$(date +%s) + echo "Elapsed Time downloading from boost webpage: $(($end-$start)) seconds" - log "Retrieving boost." + # try to use the backup boost we have in Jenkins + if [ ! -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ] || [[ $(sha256sum "${BOOST_PACKAGE_BASENAME}.tar.gz" | cut -d " " -f 1 ) != "${BOOST_SHA256SUM}" ]] ; then + log "Using boost backup" + start=$(date +%s) + wget "https://carla-releases.s3.us-east-005.backblazeb2.com/Backup/${BOOST_PACKAGE_BASENAME}.tar.gz" -O ${BOOST_PACKAGE_BASENAME}.tar.gz || true + end=$(date +%s) + echo "Elapsed Time downloading from boost carla backup in backblaze: $(($end-$start)) seconds" + fi + fi + fi + + BOOST_CXXFLAGS="${CARLA_CFLAGS} ${CARLA_CXXFLAGS}" + + if { ${SHOULD_BUILD_BOOST_SERVER} ; } ; then + rm -Rf ${BOOST_BASENAME}-server-source + + log "Extracting boost for server build." start=$(date +%s) - wget "https://archives.boost.io/release/${BOOST_VERSION}/source/${BOOST_PACKAGE_BASENAME}.tar.gz" -O ${BOOST_PACKAGE_BASENAME}.tar.gz || true + tar -xzf ${BOOST_PACKAGE_BASENAME}.tar.gz end=$(date +%s) - echo "Elapsed Time downloading from boost webpage: $(($end-$start)) seconds" + echo "Elapsed Time Extracting boost for server build: $(($end-$start)) seconds" - # try to use the backup boost we have in Jenkins - if [ ! -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ] || [[ $(sha256sum "${BOOST_PACKAGE_BASENAME}.tar.gz" | cut -d " " -f 1 ) != "${BOOST_SHA256SUM}" ]] ; then - log "Using boost backup" + mkdir -p ${BOOST_BASENAME}-server-install/include + mv ${BOOST_PACKAGE_BASENAME} ${BOOST_BASENAME}-server-source - start=$(date +%s) - wget "https://carla-releases.s3.us-east-005.backblazeb2.com/Backup/${BOOST_PACKAGE_BASENAME}.tar.gz" -O ${BOOST_PACKAGE_BASENAME}.tar.gz || true - end=$(date +%s) - echo "Elapsed Time downloading from boost carla backup in backblaze: $(($end-$start)) seconds" + pushd ${BOOST_BASENAME}-server-source >/dev/null - fi + BOOST_TOOLSET="clang-10.0" + + # Not so easy to convince Boost bootstrap to use a custom clang with custom flags. + sed -i 's/\${TOOLSET}/--cxxflags="\${CARLA_CXXFLAGS}" --cxx=\${CARLA_SERVER_CXX} \${TOOLSET}/g' ./bootstrap.sh + CARLA_CXXFLAGS="${BOOST_CXXFLAGS} ${CARLA_SERVER_CXXFLAGS} ${UNREAL_HOSTED_LINKER_FLAGS} -pthread" CARLA_SERVER_CXX=${CARLA_SERVER_CXX} ./bootstrap.sh \ + --with-toolset=clang \ + --prefix=../${BOOST_BASENAME}-server-install \ + --with-libraries=system + + # Similarly, pass the custom clang and flags to b2. + sed -i 's#using clang#using clang\n : 10.0\n : \"'"${CARLA_SERVER_CXX}"'\"\n : \"'"${BOOST_CXXFLAGS} ${CARLA_SERVER_CXXFLAGS}"'\"\n \"'"${UNREAL_HOSTED_LINKER_FLAGS}"'\"\n#g' project-config.jam - log "Extracting boost for Python ${PY_VERSION}." + ./b2 toolset="${BOOST_TOOLSET}" -j ${CARLA_BUILD_CONCURRENCY} stage release + ./b2 toolset="${BOOST_TOOLSET}" -j ${CARLA_BUILD_CONCURRENCY} install + popd >/dev/null + rm -Rf ${BOOST_BASENAME}-server-source + fi + + if { ${SHOULD_BUILD_BOOST_CLIENT} ; } ; then + rm -Rf ${BOOST_BASENAME}-client-source + + log "Extracting boost for client with Python ${PY_VERSION}." start=$(date +%s) tar -xzf ${BOOST_PACKAGE_BASENAME}.tar.gz end=$(date +%s) echo "Elapsed Time Extracting boost for Python: $(($end-$start)) seconds" - mkdir -p ${BOOST_BASENAME}-install/include - mv ${BOOST_PACKAGE_BASENAME} ${BOOST_BASENAME}-source + mkdir -p ${BOOST_BASENAME}-client-install/include + mv ${BOOST_PACKAGE_BASENAME} ${BOOST_BASENAME}-client-source + + pushd ${BOOST_BASENAME}-client-source >/dev/null - pushd ${BOOST_BASENAME}-source >/dev/null - - BOOST_TOOLSET="clang-10.0" - BOOST_CFLAGS="-fPIC -std=c++14 -DBOOST_ERROR_CODE_HEADER_ONLY" + BOOST_CFLAGS="-fPIC -std=c++17 -DBOOST_ERROR_CODE_HEADER_ONLY" py3="/usr/bin/env python${PY_VERSION}" py3_root=`${py3} -c "import sysconfig; print(sysconfig.get_config_var('prefix'))"` py3_include=$(${py3} -c "from sysconfig import get_paths as gp; print(gp()['include'])") py3_lib=$(${py3} -c "from sysconfig import get_paths as gp; print(gp()['stdlib'])") pyv=`$py3 -c "import sys;x='{v[0]}.{v[1]}'.format(v=list(sys.version_info[:2]));sys.stdout.write(x)";` + ./bootstrap.sh \ - --with-toolset=clang \ - --prefix=../boost-install \ + --with-toolset=gcc \ + --prefix=../${BOOST_BASENAME}-client-install \ --with-libraries=python,filesystem,system,program_options \ --with-python=${py3} --with-python-root=${py3_root} - if ${TRAVIS} ; then echo "using python : ${pyv} : ${py3_root}/bin/python${PY_VERSION} : \ ${py3_include} : ${py3_lib} ;" > ${HOME}/user-config.jam @@ -193,23 +259,23 @@ for PY_VERSION in ${PY_VERSION_LIST[@]} ; do ${py3_include} : ${py3_lib} ;" > project-config.jam fi - ./b2 toolset="${BOOST_TOOLSET}" cxxflags="${BOOST_CFLAGS}" --prefix="../${BOOST_BASENAME}-install" -j ${CARLA_BUILD_CONCURRENCY} stage release - ./b2 toolset="${BOOST_TOOLSET}" cxxflags="${BOOST_CFLAGS}" --prefix="../${BOOST_BASENAME}-install" -j ${CARLA_BUILD_CONCURRENCY} install + ./b2 toolset="gcc" cxxflags="${BOOST_CXXFLAGS}" -j ${CARLA_BUILD_CONCURRENCY} stage release + ./b2 toolset="gcc" cxxflags="${BOOST_CXXFLAGS}" -j ${CARLA_BUILD_CONCURRENCY} install popd >/dev/null - - rm -Rf ${BOOST_BASENAME}-source - rm ${BOOST_PACKAGE_BASENAME}.tar.gz + rm -Rf ${BOOST_BASENAME}-client-source # Install boost dependencies mkdir -p "${LIBCARLA_INSTALL_CLIENT_FOLDER}/include/system" mkdir -p "${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib" - cp -rf ${BOOST_BASENAME}-install/include/* ${LIBCARLA_INSTALL_CLIENT_FOLDER}/include/system - cp -rf ${BOOST_BASENAME}-install/lib/* ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib - + cp -rf ${BOOST_BASENAME}-client-install/include/* ${LIBCARLA_INSTALL_CLIENT_FOLDER}/include/system + cp -rf ${BOOST_BASENAME}-client-install/lib/* ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib fi done +if [ -f "${BOOST_PACKAGE_BASENAME}.tar.gz" ]; then + rm ${BOOST_PACKAGE_BASENAME}.tar.gz +fi unset BOOST_BASENAME @@ -218,20 +284,20 @@ unset BOOST_BASENAME # ============================================================================== RPCLIB_PATCH=carla-callbacks -RPCLIB_BASENAME=rpclib-${RPCLIB_PATCH}-${CXX_TAG} +RPCLIB_BASENAME=rpclib-${RPCLIB_PATCH} -RPCLIB_LIBCXX_INCLUDE=${PWD}/${RPCLIB_BASENAME}-libcxx-install/include -RPCLIB_LIBCXX_LIBPATH=${PWD}/${RPCLIB_BASENAME}-libcxx-install/lib -RPCLIB_LIBSTDCXX_INCLUDE=${PWD}/${RPCLIB_BASENAME}-libstdcxx-install/include -RPCLIB_LIBSTDCXX_LIBPATH=${PWD}/${RPCLIB_BASENAME}-libstdcxx-install/lib +RPCLIB_SERVER_INCLUDE=${PWD}/${RPCLIB_BASENAME}-server-install/include +RPCLIB_SERVER_LIBPATH=${PWD}/${RPCLIB_BASENAME}-server-install/lib +RPCLIB_CLIENT_INCLUDE=${PWD}/${RPCLIB_BASENAME}-client-install/include +RPCLIB_CLIENT_LIBPATH=${PWD}/${RPCLIB_BASENAME}-client-install/lib -if [[ -d "${RPCLIB_BASENAME}-libcxx-install" && -d "${RPCLIB_BASENAME}-libstdcxx-install" ]] ; then +if [[ -d "${RPCLIB_BASENAME}-server-install" && -d "${RPCLIB_BASENAME}-client-install" ]] ; then log "${RPCLIB_BASENAME} already installed." else rm -Rf \ ${RPCLIB_BASENAME}-source \ - ${RPCLIB_BASENAME}-libcxx-build ${RPCLIB_BASENAME}-libstdcxx-build \ - ${RPCLIB_BASENAME}-libcxx-install ${RPCLIB_BASENAME}-libstdcxx-install + ${RPCLIB_BASENAME}-server-build ${RPCLIB_BASENAME}-client-build \ + ${RPCLIB_BASENAME}-server-install ${RPCLIB_BASENAME}-client-install log "Retrieving rpclib." @@ -248,13 +314,13 @@ else # As cmake 3.9 is not standard in Ubuntu 16.04, change cmake version to 3.5 sed -i s/"3.9.0"/"3.5.0"/g ${RPCLIB_BASENAME}-source/CMakeLists.txt - mkdir -p ${RPCLIB_BASENAME}-libcxx-build + mkdir -p ${RPCLIB_BASENAME}-server-build - pushd ${RPCLIB_BASENAME}-libcxx-build >/dev/null + pushd ${RPCLIB_BASENAME}-server-build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH} -DBOOST_NO_EXCEPTIONS -DASIO_NO_EXCEPTIONS ${UNREAL_HOSTED_CFLAGS}" \ - -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-libcxx-install" \ + -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-server-install" \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_SERVER_TOOLCHAIN_FILE}" \ ../${RPCLIB_BASENAME}-source ninja @@ -265,13 +331,13 @@ else log "Building rpclib with libstdc++." - mkdir -p ${RPCLIB_BASENAME}-libstdcxx-build + mkdir -p ${RPCLIB_BASENAME}-client-build - pushd ${RPCLIB_BASENAME}-libstdcxx-build >/dev/null + pushd ${RPCLIB_BASENAME}-client-build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++14" \ - -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-libstdcxx-install" \ + -DCMAKE_INSTALL_PREFIX="../${RPCLIB_BASENAME}-client-install" \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_CLIENT_TOOLCHAIN_FILE}" \ ../${RPCLIB_BASENAME}-source ninja @@ -280,7 +346,7 @@ else popd >/dev/null - rm -Rf ${RPCLIB_BASENAME}-source ${RPCLIB_BASENAME}-libcxx-build ${RPCLIB_BASENAME}-libstdcxx-build + rm -Rf ${RPCLIB_BASENAME}-source ${RPCLIB_BASENAME}-server-build ${RPCLIB_BASENAME}-client-build fi @@ -291,20 +357,20 @@ unset RPCLIB_BASENAME # ============================================================================== GTEST_VERSION=1.8.1 -GTEST_BASENAME=gtest-${GTEST_VERSION}-${CXX_TAG} +GTEST_BASENAME=gtest-${GTEST_VERSION} -GTEST_LIBCXX_INCLUDE=${PWD}/${GTEST_BASENAME}-libcxx-install/include -GTEST_LIBCXX_LIBPATH=${PWD}/${GTEST_BASENAME}-libcxx-install/lib -GTEST_LIBSTDCXX_INCLUDE=${PWD}/${GTEST_BASENAME}-libstdcxx-install/include -GTEST_LIBSTDCXX_LIBPATH=${PWD}/${GTEST_BASENAME}-libstdcxx-install/lib +GTEST_SERVER_INCLUDE=${PWD}/${GTEST_BASENAME}-server-install/include +GTEST_SERVER_LIBPATH=${PWD}/${GTEST_BASENAME}-server-install/lib +GTEST_CLIENT_INCLUDE=${PWD}/${GTEST_BASENAME}-client-install/include +GTEST_CLIENT_LIBPATH=${PWD}/${GTEST_BASENAME}-client-install/lib -if [[ -d "${GTEST_BASENAME}-libcxx-install" && -d "${GTEST_BASENAME}-libstdcxx-install" ]] ; then +if [[ -d "${GTEST_BASENAME}-server-install" && -d "${GTEST_BASENAME}-client-install" ]] ; then log "${GTEST_BASENAME} already installed." else rm -Rf \ ${GTEST_BASENAME}-source \ - ${GTEST_BASENAME}-libcxx-build ${GTEST_BASENAME}-libstdcxx-build \ - ${GTEST_BASENAME}-libcxx-install ${GTEST_BASENAME}-libstdcxx-install + ${GTEST_BASENAME}-server-build ${GTEST_BASENAME}-client-build \ + ${GTEST_BASENAME}-server-install ${GTEST_BASENAME}-client-install log "Retrieving Google Test." @@ -317,13 +383,13 @@ else log "Building Google Test with libc++." - mkdir -p ${GTEST_BASENAME}-libcxx-build + mkdir -p ${GTEST_BASENAME}-server-build - pushd ${GTEST_BASENAME}-libcxx-build >/dev/null + pushd ${GTEST_BASENAME}-server-build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH} -DBOOST_NO_EXCEPTIONS -fno-exceptions ${UNREAL_HOSTED_CFLAGS}" \ - -DCMAKE_INSTALL_PREFIX="../${GTEST_BASENAME}-libcxx-install" \ + -DCMAKE_INSTALL_PREFIX="../${GTEST_BASENAME}-server-install" \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_SERVER_TOOLCHAIN_FILE}" \ ../${GTEST_BASENAME}-source ninja @@ -334,13 +400,13 @@ else log "Building Google Test with libstdc++." - mkdir -p ${GTEST_BASENAME}-libstdcxx-build + mkdir -p ${GTEST_BASENAME}-client-build - pushd ${GTEST_BASENAME}-libstdcxx-build >/dev/null + pushd ${GTEST_BASENAME}-client-build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-std=c++14" \ - -DCMAKE_INSTALL_PREFIX="../${GTEST_BASENAME}-libstdcxx-install" \ + -DCMAKE_INSTALL_PREFIX="../${GTEST_BASENAME}-client-install" \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_CLIENT_TOOLCHAIN_FILE}" \ ../${GTEST_BASENAME}-source ninja @@ -349,7 +415,7 @@ else popd >/dev/null - rm -Rf ${GTEST_BASENAME}-source ${GTEST_BASENAME}-libcxx-build ${GTEST_BASENAME}-libstdcxx-build + rm -Rf ${GTEST_BASENAME}-source ${GTEST_BASENAME}-server-build ${GTEST_BASENAME}-client-build fi @@ -359,7 +425,7 @@ unset GTEST_BASENAME # -- Get Recast&Detour and compile it with libc++ ------------------------------ # ============================================================================== -RECAST_BASENAME=recast-${CXX_TAG} +RECAST_BASENAME=recast RECAST_INCLUDE=${PWD}/${RECAST_BASENAME}-install/include RECAST_LIBPATH=${PWD}/${RECAST_BASENAME}-install/lib @@ -393,8 +459,8 @@ else pushd ${RECAST_BASENAME}-build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-std=c++14 -fPIC" \ -DCMAKE_INSTALL_PREFIX="../${RECAST_BASENAME}-install" \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_CLIENT_TOOLCHAIN_FILE}" \ -DRECASTNAVIGATION_DEMO=False \ -DRECASTNAVIGATION_TEST=False \ ../${RECAST_BASENAME}-source @@ -469,12 +535,12 @@ XERCESC_TEMP_FOLDER=${XERCESC_BASENAME} XERCESC_REPO=https://archive.apache.org/dist/xerces/c/3/sources/xerces-c-${XERCESC_VERSION}.tar.gz XERCESC_SRC_DIR=${XERCESC_BASENAME}-source -XERCESC_INSTALL_DIR=${XERCESC_BASENAME}-install -XERCESC_INSTALL_SERVER_DIR=${XERCESC_BASENAME}-install-server -XERCESC_LIB=${XERCESC_INSTALL_DIR}/lib/libxerces-c.a +XERCESC_INSTALL_CLIENT_DIR=${XERCESC_BASENAME}-client-install +XERCESC_INSTALL_SERVER_DIR=${XERCESC_BASENAME}-server-install +XERCESC_CLIENT_LIB=${XERCESC_INSTALL_CLIENT_DIR}/lib/libxerces-c.a XERCESC_SERVER_LIB=${XERCESC_INSTALL_SERVER_DIR}/lib/libxerces-c.a -if [[ -d ${XERCESC_INSTALL_DIR} && -d ${XERCESC_INSTALL_SERVER_DIR} ]] ; then +if [[ -d ${XERCESC_INSTALL_CLIENT_DIR} && -d ${XERCESC_INSTALL_SERVER_DIR} ]] ; then log "Xerces-c already installed." else log "Retrieving xerces-c." @@ -499,14 +565,14 @@ else echo "Elapsed Time Extracting xerces-c: $(($end-$start)) seconds" mv ${XERCESC_BASENAME} ${XERCESC_SRC_DIR} - mkdir -p ${XERCESC_INSTALL_DIR} - mkdir -p ${XERCESC_SRC_DIR}/build + mkdir -p ${XERCESC_INSTALL_CLIENT_DIR} - pushd ${XERCESC_SRC_DIR}/build >/dev/null + mkdir -p ${XERCESC_SRC_DIR}/client-build + pushd ${XERCESC_SRC_DIR}/client-build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-std=c++14 -fPIC -w" \ - -DCMAKE_INSTALL_PREFIX="../../${XERCESC_INSTALL_DIR}" \ + -DCMAKE_INSTALL_PREFIX="../../${XERCESC_INSTALL_CLIENT_DIR}" \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_CLIENT_TOOLCHAIN_FILE}" \ -DCMAKE_BUILD_TYPE=Release \ -DBUILD_SHARED_LIBS=OFF \ -Dtranscoder=gnuiconv \ @@ -519,11 +585,13 @@ else mkdir -p ${XERCESC_INSTALL_SERVER_DIR} - pushd ${XERCESC_SRC_DIR}/build >/dev/null + + mkdir -p ${XERCESC_SRC_DIR}/server-build + pushd ${XERCESC_SRC_DIR}/server-build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-std=c++14 -stdlib=libc++ -fPIC -w -I${LLVM_INCLUDE} -L${LLVM_LIBPATH}" \ -DCMAKE_INSTALL_PREFIX="../../${XERCESC_INSTALL_SERVER_DIR}" \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_SERVER_TOOLCHAIN_FILE}" \ -DCMAKE_BUILD_TYPE=Release \ -DBUILD_SHARED_LIBS=OFF \ -Dtranscoder=gnuiconv \ @@ -539,7 +607,7 @@ else fi mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ -cp ${XERCESC_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ +cp ${XERCESC_CLIENT_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ cp -p ${XERCESC_SERVER_LIB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ @@ -617,7 +685,8 @@ if ${USE_CHRONO} ; then mkdir -p ${CHRONO_SRC_DIR}/build pushd ${CHRONO_SRC_DIR}/build >/dev/null cmake -G "Ninja" \ - -DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -L${LLVM_LIBPATH} -Wno-unused-command-line-argument ${UNREAL_HOSTED_CFLAGS}" \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_SERVER_TOOLCHAIN_FILE}" \ + -DCMAKE_CXX_FLAGS="-Wno-unused-command-line-argument" \ -DEIGEN3_INCLUDE_DIR="${EIGEN_INCLUDE}" \ -DCMAKE_INSTALL_PREFIX="${CARLA_BUILD_FOLDER}/${CHRONO_INSTALL_DIR}" \ -DCMAKE_BUILD_TYPE=Release \ @@ -645,19 +714,25 @@ fi SQLITE_VERSION=sqlite-autoconf-3340100 SQLITE_REPO=https://www.sqlite.org/2021/${SQLITE_VERSION}.tar.gz - SQLITE_TAR=${SQLITE_VERSION}.tar.gz -SQLITE_SOURCE_DIR=sqlite-src -SQLITE_INSTALL_DIR=sqlite-install +SQLITE_BASENAME=sqlite -SQLITE_INCLUDE_DIR=${PWD}/${SQLITE_INSTALL_DIR}/include -SQLITE_LIB=${PWD}/${SQLITE_INSTALL_DIR}/lib/libsqlite3.a -SQLITE_FULL_LIB=${PWD}/${SQLITE_INSTALL_DIR}/lib/ -SQLITE_EXE=${PWD}/${SQLITE_INSTALL_DIR}/bin/sqlite3 +SQLITE_SERVER_INCLUDE_DIR=${PWD}/${SQLITE_BASENAME}-server-install/include +SQLITE_SERVER_LIB=${PWD}/${SQLITE_BASENAME}-server-install/lib/libsqlite3.a +SQLITE_SERVER_LIB_FOLDER=${PWD}/${SQLITE_BASENAME}-server-install/lib/ +SQLITE_CLIENT_INCLUDE_DIR=${PWD}/${SQLITE_BASENAME}-client-install/include +SQLITE_CLIENT_LIB=${PWD}/${SQLITE_BASENAME}-client-install/lib/libsqlite3.a +SQLITE_EXE=${PWD}/${SQLITE_BASENAME}-client-install/bin/sqlite3 -if [[ -d ${SQLITE_INSTALL_DIR} ]] ; then +if [[ -d ${SQLITE_BASENAME}-server-install && -d ${SQLITE_BASENAME}-client-install ]] ; then log "Sqlite already installed." else + rm -Rf \ + ${SQLITE_BASENAME}-source \ + ${SQLITE_BASENAME}-build \ + ${SQLITE_BASENAME}-client-install \ + ${SQLITE_BASENAME}-server-install + log "Retrieving Sqlite3" start=$(date +%s) @@ -672,28 +747,28 @@ else end=$(date +%s) echo "Elapsed Time Extracting for SQlite: $(($end-$start)) seconds" - mv ${SQLITE_VERSION} ${SQLITE_SOURCE_DIR} - - mkdir ${SQLITE_INSTALL_DIR} + mv ${SQLITE_VERSION} ${SQLITE_BASENAME}-source - pushd ${SQLITE_SOURCE_DIR} >/dev/null - - export CFLAGS="-fPIC -w" - ./configure --prefix=${PWD}/../sqlite-install/ - make + mkdir ${SQLITE_BASENAME}-client-build + pushd ${SQLITE_BASENAME}-client-build >/dev/null + ../${SQLITE_BASENAME}-source/configure CFLAGS="${CARLA_CFLAGS} -w" --prefix=${PWD}/../${SQLITE_BASENAME}-client-install/ make install + popd >/dev/null + mkdir ${SQLITE_BASENAME}-server-build + pushd ${SQLITE_BASENAME}-server-build >/dev/null + ../${SQLITE_BASENAME}-source/configure CFLAGS="${CARLA_SERVER_CFLAGS} -w" --prefix=${PWD}/../${SQLITE_BASENAME}-server-install/ + make install popd >/dev/null + rm -Rf ${SQLITE_TAR} - rm -Rf ${SQLITE_SOURCE_DIR} + rm -Rf ${SQLITE_BASENAME}-source ${SQLITE_BASENAME}-client-build ${SQLITE_BASENAME}-server-build fi -mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ -cp ${SQLITE_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ +cp ${SQLITE_CLIENT_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ +cp -p -r ${SQLITE_SERVER_LIB_FOLDER}/* ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ -mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ -cp -p -r ${SQLITE_FULL_LIB} ${LIBCARLA_INSTALL_SERVER_FOLDER} # ============================================================================== # -- Get and compile PROJ ------------------------------------------------------ @@ -704,14 +779,14 @@ PROJ_REPO=https://download.osgeo.org/proj/${PROJ_VERSION}.tar.gz PROJ_TAR=${PROJ_VERSION}.tar.gz PROJ_SRC_DIR=proj-src -PROJ_INSTALL_DIR=proj-install -PROJ_INSTALL_SERVER_DIR=proj-install-server -PROJ_INSTALL_DIR_FULL=${PWD}/${PROJ_INSTALL_DIR} +PROJ_INSTALL_CLIENT_DIR=proj-client-install +PROJ_INSTALL_SERVER_DIR=proj-server-install +PROJ_INSTALL_CLIENT_DIR_FULL=${PWD}/${PROJ_INSTALL_CLIENT_DIR} PROJ_INSTALL_SERVER_DIR_FULL=${PWD}/${PROJ_INSTALL_SERVER_DIR} -PROJ_LIB=${PROJ_INSTALL_DIR_FULL}/lib/libproj.a +PROJ_CLIENT_LIB=${PROJ_INSTALL_CLIENT_DIR_FULL}/lib/libproj.a PROJ_SERVER_LIB=${PROJ_INSTALL_SERVER_DIR_FULL}/lib/libproj.a -if [[ -d ${PROJ_INSTALL_DIR} && -d ${PROJ_INSTALL_SERVER_DIR_FULL} ]] ; then +if [[ -d ${PROJ_INSTALL_CLIENT_DIR} && -d ${PROJ_INSTALL_SERVER_DIR_FULL} ]] ; then log "PROJ already installed." else log "Retrieving PROJ" @@ -728,21 +803,23 @@ else echo "Elapsed Time Extracting for PROJ: $(($end-$start)) seconds" mv ${PROJ_VERSION} ${PROJ_SRC_DIR} + # fix missing include + sed -e 's/#include /#include \n#include /g' -i ${PROJ_SRC_DIR}/src/proj_json_streaming_writer.hpp - mkdir -p ${PROJ_SRC_DIR}/build - mkdir -p ${PROJ_INSTALL_DIR} + mkdir -p ${PROJ_SRC_DIR}/client-build + mkdir -p ${PROJ_INSTALL_CLIENT_DIR} - pushd ${PROJ_SRC_DIR}/build >/dev/null + pushd ${PROJ_SRC_DIR}/client-build >/dev/null cmake -G "Ninja" .. \ - -DCMAKE_CXX_FLAGS="-std=c++14 -fPIC" \ - -DSQLITE3_INCLUDE_DIR=${SQLITE_INCLUDE_DIR} -DSQLITE3_LIBRARY=${SQLITE_LIB} \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_CLIENT_TOOLCHAIN_FILE}" \ + -DSQLITE3_INCLUDE_DIR=${SQLITE_CLIENT_INCLUDE_DIR} -DSQLITE3_LIBRARY=${SQLITE_CLIENT_LIB} \ -DEXE_SQLITE3=${SQLITE_EXE} \ -DENABLE_TIFF=OFF -DENABLE_CURL=OFF -DBUILD_SHARED_LIBS=OFF -DBUILD_PROJSYNC=OFF \ -DCMAKE_BUILD_TYPE=Release -DBUILD_PROJINFO=OFF \ -DBUILD_CCT=OFF -DBUILD_CS2CS=OFF -DBUILD_GEOD=OFF -DBUILD_GIE=OFF \ -DBUILD_PROJ=OFF -DBUILD_TESTING=OFF \ - -DCMAKE_INSTALL_PREFIX=${PROJ_INSTALL_DIR_FULL} + -DCMAKE_INSTALL_PREFIX=${PROJ_INSTALL_CLIENT_DIR_FULL} ninja ninja install @@ -750,11 +827,12 @@ else mkdir -p ${PROJ_INSTALL_SERVER_DIR} - pushd ${PROJ_SRC_DIR}/build >/dev/null + mkdir -p ${PROJ_SRC_DIR}/server-build + pushd ${PROJ_SRC_DIR}/server-build >/dev/null cmake -G "Ninja" .. \ - -DCMAKE_CXX_FLAGS="-std=c++14 -fPIC -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH}" \ - -DSQLITE3_INCLUDE_DIR=${SQLITE_INCLUDE_DIR} -DSQLITE3_LIBRARY=${SQLITE_LIB} \ + -DCMAKE_TOOLCHAIN_FILE="${CARLA_SERVER_TOOLCHAIN_FILE}" \ + -DSQLITE3_INCLUDE_DIR=${SQLITE_SERVER_INCLUDE_DIR} -DSQLITE3_LIBRARY=${SQLITE_SERVER_LIB} \ -DEXE_SQLITE3=${SQLITE_EXE} \ -DENABLE_TIFF=OFF -DENABLE_CURL=OFF -DBUILD_SHARED_LIBS=OFF -DBUILD_PROJSYNC=OFF \ -DCMAKE_BUILD_TYPE=Release -DBUILD_PROJINFO=OFF \ @@ -771,7 +849,7 @@ else fi -cp ${PROJ_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ +cp ${PROJ_CLIENT_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/ mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ cp -p ${PROJ_SERVER_LIB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/ @@ -937,7 +1015,7 @@ if ${USE_ROS2} ; then pushd ${FOONATHAN_MEMORY_VENDOR_SOURCE_DIR}/build >/dev/null cmake -G "Ninja" \ -DCMAKE_INSTALL_PREFIX="${FASTDDS_INSTALL_DIR}" \ - -DCMAKE_TOOLCHAIN_FILE=${LIBCPP_TOOLCHAIN_FILE} \ + -DCMAKE_TOOLCHAIN_FILE=${CARLA_SERVER_TOOLCHAIN_FILE} \ -DBUILD_SHARED_LIBS=OFF \ -DFOONATHAN_MEMORY_FORCE_VENDORED_BUILD=ON \ .. @@ -950,8 +1028,8 @@ if ${USE_ROS2} ; then FAST_DDS_LIB_BASENAME=fast-dds-lib FAST_DDS_LIB_SOURCE_DIR=${PWD}/${FAST_DDS_LIB_BASENAME}-source FAST_DDS_LIB_REPO="https://github.com/eProsima/Fast-DDS.git" - FAST_DDS_LIB_BRANCH=v2.11.2 - + FAST_DDS_LIB_BRANCH=v2.14.6 + git clone --recurse-submodules --depth 1 --branch ${FAST_DDS_LIB_BRANCH} ${FAST_DDS_LIB_REPO} ${FAST_DDS_LIB_SOURCE_DIR} # copy OpenSSL from UE4 @@ -962,22 +1040,26 @@ 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. + + # 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 exceptions, occuring exceptions are forwarded to CARLA server and the program gets + # finished, which is not desired behaviour + # => remove -DASIO_NO_EXCEPTIONS and -DBOOST_NO_EXCEPTIONS from toolchain file + sed -e "s|\-DASIO_NO_EXCEPTIONS||g" ${CARLA_SERVER_TOOLCHAIN_FILE} > ${CARLA_SERVER_TOOLCHAIN_FILE}.fastdds + sed -e "s|\-DBOOST_NO_EXCEPTIONS||g" -i ${CARLA_SERVER_TOOLCHAIN_FILE}.fastdds + 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_TOOLCHAIN_FILE=${CARLA_SERVER_TOOLCHAIN_FILE}.fastdds \ -DBUILD_SHARED_LIBS=OFF \ -DBUILD_TESTING=OFF \ -DCOMPILE_EXAMPLES=OFF \ @@ -990,7 +1072,7 @@ if ${USE_ROS2} ; then -DOPENSSL_INCLUDE_DIR:FILEPATH=${FASTDDS_INCLUDE} \ -DOPENSSL_SSL_LIBRARY:FILEPATH=${FASTDDS_LIB}/libssl.a \ -DOPENSSL_CRYPTO_LIBRARY:FILEPATH=${FASTDDS_LIB}/libcrypto.a \ - -DTHIRDPARTY_BOOST_INCLUDE_DIR="${BOOST_INCLUDE};${FAST_DDS_LIB_SOURCE_DIR}/thirdparty/boost/include" \ + -DTHIRDPARTY_BOOST_INCLUDE_DIR="${BOOST_SERVER_INCLUDE};${FAST_DDS_LIB_SOURCE_DIR}/thirdparty/boost/include" \ .. ninja ninja install @@ -1027,7 +1109,7 @@ cat >${CMAKE_CONFIG_FILE}.gen <