From 3ba11fa882d59d974b2c043a415948bc39f10efb Mon Sep 17 00:00:00 2001 From: Knese Karsten Date: Sat, 23 May 2020 12:30:19 -0700 Subject: [PATCH] all tests pass now Signed-off-by: Knese Karsten --- .../rmw_iceoryx_cpp/iceoryx_deserialize.hpp | 4 +- .../iceoryx_name_conversion.hpp | 20 +- .../rmw_iceoryx_cpp/iceoryx_serialize.hpp | 4 +- .../iceoryx_topic_names_and_types.hpp | 7 +- .../iceoryx_type_info_introspection.hpp | 9 +- rmw_iceoryx_cpp/src/iceoryx_identifier.hpp | 3 +- .../src/iceoryx_serialization_format.hpp | 3 +- .../src/internal/iceoryx_deserialize.cpp | 12 +- .../iceoryx_deserialize_typesupport_c.hpp | 87 +-- .../iceoryx_deserialize_typesupport_cpp.hpp | 132 ++-- .../src/internal/iceoryx_name_conversion.cpp | 33 +- .../internal/iceoryx_serialization_common.hpp | 10 +- .../src/internal/iceoryx_serialize.cpp | 12 +- .../iceoryx_serialize_typesupport_c.hpp | 55 +- .../iceoryx_serialize_typesupport_cpp.hpp | 89 +-- .../iceoryx_topic_names_and_types.cpp | 20 +- .../iceoryx_type_info_introspection.cpp | 33 +- rmw_iceoryx_cpp/src/rmw_client.cpp | 17 +- .../src/rmw_compare_guids_equal.cpp | 9 +- rmw_iceoryx_cpp/src/rmw_count.cpp | 27 +- rmw_iceoryx_cpp/src/rmw_event.cpp | 21 +- .../src/rmw_get_gid_for_publisher.cpp | 6 +- .../src/rmw_get_implementation_identifier.cpp | 9 +- .../src/rmw_get_serialization_format.cpp | 9 +- .../src/rmw_get_topic_endpoint_info.cpp | 27 +- rmw_iceoryx_cpp/src/rmw_guard_condition.cpp | 31 +- rmw_iceoryx_cpp/src/rmw_init.cpp | 36 +- rmw_iceoryx_cpp/src/rmw_logging.cpp | 6 +- rmw_iceoryx_cpp/src/rmw_node.cpp | 49 +- .../src/rmw_node_info_and_types.cpp | 53 +- rmw_iceoryx_cpp/src/rmw_node_names.cpp | 30 +- rmw_iceoryx_cpp/src/rmw_publish.cpp | 45 +- rmw_iceoryx_cpp/src/rmw_publisher.cpp | 57 +- rmw_iceoryx_cpp/src/rmw_request.cpp | 17 +- rmw_iceoryx_cpp/src/rmw_response.cpp | 17 +- rmw_iceoryx_cpp/src/rmw_serialize.cpp | 28 +- rmw_iceoryx_cpp/src/rmw_service.cpp | 15 +- .../src/rmw_service_names_and_types.cpp | 9 +- .../src/rmw_service_server_is_available.cpp | 10 +- rmw_iceoryx_cpp/src/rmw_subscription.cpp | 52 +- rmw_iceoryx_cpp/src/rmw_take.cpp | 107 ++-- .../src/rmw_topic_names_and_types.cpp | 14 +- .../src/rmw_trigger_guard_condition.cpp | 9 +- rmw_iceoryx_cpp/src/rmw_wait.cpp | 17 +- rmw_iceoryx_cpp/src/rmw_wait_set.cpp | 28 +- .../src/types/iceoryx_guard_condition.hpp | 20 +- rmw_iceoryx_cpp/src/types/iceoryx_node.hpp | 9 +- .../src/types/iceoryx_publisher.hpp | 3 +- .../src/types/iceoryx_subscription.hpp | 3 +- .../src/types/iceoryx_wait_set.hpp | 6 +- .../test/iceoryx_name_conversion_test.cpp | 46 +- .../test/iceoryx_serialization_test.cpp | 52 +- rmw_iceoryx_cpp/test/test_msgs_c_fixtures.hpp | 565 ++++++++++++------ 53 files changed, 871 insertions(+), 1121 deletions(-) diff --git a/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_deserialize.hpp b/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_deserialize.hpp index fd32457..02df519 100644 --- a/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_deserialize.hpp +++ b/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_deserialize.hpp @@ -19,11 +19,9 @@ struct rosidl_message_type_support_t; namespace rmw_iceoryx_cpp { - // TODO(karsten1987): This should be `uint8`, really void deserialize( - const char * serialized_msg, - const rosidl_message_type_support_t * type_supports, + const char * serialized_msg, const rosidl_message_type_support_t * type_supports, void * ros_message); } // namespace rmw_iceoryx_cpp diff --git a/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_name_conversion.hpp b/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_name_conversion.hpp index bd38098..b158c0b 100644 --- a/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_name_conversion.hpp +++ b/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_name_conversion.hpp @@ -25,7 +25,6 @@ class rosidl_message_type_support_t; namespace rmw_iceoryx_cpp { - /// Get the pair of ROS topic and type from a given iceoryx service triplet. /** * Given a triplet of `service`, `instance`, `event`, convert these to a ROS2 conform @@ -36,11 +35,8 @@ namespace rmw_iceoryx_cpp * \param event the iceoryx event description * \return tuple of topic and type */ -std::tuple -get_name_n_type_from_service_description( - const std::string & service, - const std::string & instance, - const std::string & event); +std::tuple get_name_n_type_from_service_description( + const std::string & service, const std::string & instance, const std::string & event); /// Get the iceoryx service triplet description from a given pair of ROS topic and type. /** @@ -51,15 +47,11 @@ get_name_n_type_from_service_description( * \param event the iceoryx event description * \return triple of iceoryx `service`, `instance`, `event`. */ -std::tuple -get_service_description_from_name_n_type( - const std::string & topic_name, - const std::string & type_name); +std::tuple get_service_description_from_name_n_type( + const std::string & topic_name, const std::string & type_name); -iox::capro::ServiceDescription -get_iceoryx_service_description( - const std::string & topic, - const rosidl_message_type_support_t * type_supports); +iox::capro::ServiceDescription get_iceoryx_service_description( + const std::string & topic, const rosidl_message_type_support_t * type_supports); } // namespace rmw_iceoryx_cpp #endif // RMW_ICEORYX_CPP__ICEORYX_NAME_CONVERSION_HPP_ diff --git a/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_serialize.hpp b/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_serialize.hpp index 8f37463..7f66403 100644 --- a/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_serialize.hpp +++ b/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_serialize.hpp @@ -21,10 +21,8 @@ struct rosidl_message_type_support_t; namespace rmw_iceoryx_cpp { - void serialize( - const void * ros_message, - const rosidl_message_type_support_t * type_supports, + const void * ros_message, const rosidl_message_type_support_t * type_supports, std::vector & payload_vector); } // namespace rmw_iceoryx_cpp diff --git a/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_topic_names_and_types.hpp b/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_topic_names_and_types.hpp index d938d8e..961a744 100644 --- a/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_topic_names_and_types.hpp +++ b/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_topic_names_and_types.hpp @@ -26,7 +26,6 @@ namespace rmw_iceoryx_cpp { - std::map get_topic_names_and_types(); std::map> get_nodes_and_publishers(); @@ -34,12 +33,10 @@ std::map> get_nodes_and_publishers(); std::map> get_nodes_and_subscribers(); std::map get_publisher_names_and_types_of_node( - const char * node_name, - const char * node_namespace); + const char * node_name, const char * node_namespace); std::map get_subscription_names_and_types_of_node( - const char * node_name, - const char * node_namespace); + const char * node_name, const char * node_namespace); rmw_ret_t fill_rmw_names_and_types( rmw_names_and_types_t * rmw_topic_names_and_types, diff --git a/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_type_info_introspection.hpp b/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_type_info_introspection.hpp index f1ffe68..ca3ffd3 100644 --- a/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_type_info_introspection.hpp +++ b/rmw_iceoryx_cpp/include/rmw_iceoryx_cpp/iceoryx_type_info_introspection.hpp @@ -21,7 +21,6 @@ class rosidl_message_type_support_t; namespace rmw_iceoryx_cpp { - bool iceoryx_is_fixed_size(const rosidl_message_type_support_t * type_supports); bool iceoryx_is_valid_type_support(const rosidl_message_type_support_t * type_supports); @@ -32,13 +31,9 @@ std::string iceoryx_get_message_name(const rosidl_message_type_support_t * type_ std::string iceoryx_get_message_namespace(const rosidl_message_type_support_t * type_supports); -void iceoryx_init_message( - const rosidl_message_type_support_t * type_supports, - void * message); +void iceoryx_init_message(const rosidl_message_type_support_t * type_supports, void * message); -void iceoryx_fini_message( - const rosidl_message_type_support_t * type_supports, - void * message); +void iceoryx_fini_message(const rosidl_message_type_support_t * type_supports, void * message); } // namespace rmw_iceoryx_cpp #endif // RMW_ICEORYX_CPP__ICEORYX_TYPE_INFO_INTROSPECTION_HPP_ diff --git a/rmw_iceoryx_cpp/src/iceoryx_identifier.hpp b/rmw_iceoryx_cpp/src/iceoryx_identifier.hpp index ea1ced8..9cb9118 100644 --- a/rmw_iceoryx_cpp/src/iceoryx_identifier.hpp +++ b/rmw_iceoryx_cpp/src/iceoryx_identifier.hpp @@ -15,8 +15,7 @@ #ifndef ICEORYX_IDENTIFIER_HPP_ #define ICEORYX_IDENTIFIER_HPP_ -extern "C" -{ +extern "C" { extern const char * const rmw_iceoryx_cpp_identifier; } // extern "C" #endif // ICEORYX_IDENTIFIER_HPP_ diff --git a/rmw_iceoryx_cpp/src/iceoryx_serialization_format.hpp b/rmw_iceoryx_cpp/src/iceoryx_serialization_format.hpp index 5ce5f6d..7e8586c 100644 --- a/rmw_iceoryx_cpp/src/iceoryx_serialization_format.hpp +++ b/rmw_iceoryx_cpp/src/iceoryx_serialization_format.hpp @@ -15,8 +15,7 @@ #ifndef ICEORYX_SERIALIZATION_FORMAT_HPP_ #define ICEORYX_SERIALIZATION_FORMAT_HPP_ -extern "C" -{ +extern "C" { extern const char * const iceoryx_serialization_format; } // extern "C" #endif // ICEORYX_SERIALIZATION_FORMAT_HPP_ diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize.cpp b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize.cpp index 226f0ee..a579e3d 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize.cpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize.cpp @@ -27,16 +27,13 @@ namespace rmw_iceoryx_cpp { - void deserialize( - const char * serialized_msg, - const rosidl_message_type_support_t * type_supports, + const char * serialized_msg, const rosidl_message_type_support_t * type_supports, void * ros_message) { // serialize with cpp typesupport auto ts_cpp = get_message_typesupport_handle( - type_supports, - rosidl_typesupport_introspection_cpp::typesupport_identifier); + type_supports, rosidl_typesupport_introspection_cpp::typesupport_identifier); if (ts_cpp != nullptr) { auto members = static_cast(ts_cpp->data); @@ -44,9 +41,8 @@ void deserialize( } // serialize with c typesupport - auto ts_c = get_message_typesupport_handle( - type_supports, - rosidl_typesupport_introspection_c__identifier); + auto ts_c = + get_message_typesupport_handle(type_supports, rosidl_typesupport_introspection_c__identifier); if (ts_c != nullptr) { auto members = static_cast(ts_c->data); diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_c.hpp b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_c.hpp index 40f1ece..eedb4a6 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_c.hpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_c.hpp @@ -12,7 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#pragma once +#ifndef INTERNAL__ICEORYX_DESERIALIZE_TYPESUPPORT_C_HPP_ +#define INTERNAL__ICEORYX_DESERIALIZE_TYPESUPPORT_C_HPP_ #include #include @@ -33,14 +34,8 @@ namespace rmw_iceoryx_cpp { namespace details_c { - -template< - class T, - size_t SizeT = sizeof(T) -> -const char * deserialize_element( - const char * serialized_msg, - void * ros_message_field) +template +const char * deserialize_element(const char * serialized_msg, void * ros_message_field) { T * data = reinterpret_cast(ros_message_field); memcpy(data, serialized_msg, SizeT); @@ -51,8 +46,7 @@ const char * deserialize_element( template<> const char * deserialize_element( - const char * serialized_msg, - void * ros_message_field) + const char * serialized_msg, void * ros_message_field) { uint32_t string_size = 0; std::tie(serialized_msg, string_size) = pop_sequence_size(serialized_msg); @@ -65,10 +59,7 @@ const char * deserialize_element -const char * deserialize_array( - const char * serialized_msg, - void * ros_message_field, - uint32_t size) +const char * deserialize_array(const char * serialized_msg, void * ros_message_field, uint32_t size) { auto array = reinterpret_cast(ros_message_field); for (size_t i = 0; i < size; ++i) { @@ -78,10 +69,7 @@ const char * deserialize_array( return serialized_msg; } -template< - class T, - size_t SizeT = sizeof(T) -> +template const char * deserialize_sequence(const char * serialized_msg, void * ros_message_field) { uint32_t array_size = 0; @@ -100,8 +88,7 @@ const char * deserialize_sequence(const char * serialized_msg, void * ros_messag template<> const char * deserialize_sequence( - const char * serialized_msg, - void * ros_message_field) + const char * serialized_msg, void * ros_message_field) { uint32_t array_size = 0; std::tie(serialized_msg, array_size) = pop_sequence_size(serialized_msg); @@ -119,8 +106,8 @@ const char * deserialize_sequence( template const char * deserialize_message_field( - const rosidl_typesupport_introspection_c__MessageMember * member, - const char * serialized_msg, void * ros_message_field) + const rosidl_typesupport_introspection_c__MessageMember * member, const char * serialized_msg, + void * ros_message_field) { debug_log("deserializing %s\n", member->name_); if (!member->is_array_) { @@ -133,8 +120,7 @@ const char * deserialize_message_field( } const char * deserialize( - const char * serialized_msg, - const rosidl_typesupport_introspection_c__MessageMembers * members, + const char * serialized_msg, const rosidl_typesupport_introspection_c__MessageMembers * members, void * ros_message) { for (uint32_t i = 0; i < members->member_count_; ++i) { @@ -146,9 +132,8 @@ const char * deserialize( break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_BYTE: case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT8: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_CHAR: case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT8: @@ -163,42 +148,34 @@ const char * deserialize( deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT16: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT16: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT32: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT32: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_INT64: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_UINT64: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_STRING: serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + member, serialized_msg, ros_message_field); break; - case ::rosidl_typesupport_introspection_c__ROS_TYPE_MESSAGE: - { + case ::rosidl_typesupport_introspection_c__ROS_TYPE_MESSAGE: { auto sub_members = (const rosidl_typesupport_introspection_c__MessageMembers *)member->members_->data; @@ -217,10 +194,8 @@ const char * deserialize( std::tie(serialized_msg, sequence_size) = pop_sequence_size(serialized_msg); - auto sequence = - const_cast(reinterpret_cast(ros_message_field)); + auto sequence = const_cast( + reinterpret_cast(ros_message_field)); subros_message = reinterpret_cast(sequence->data); } @@ -229,8 +204,7 @@ const char * deserialize( serialized_msg = deserialize(serialized_msg, sub_members, subros_message); subros_message = static_cast(subros_message) + sub_members_size; } - } - break; + } break; default: throw std::runtime_error("unknown type"); } @@ -240,3 +214,4 @@ const char * deserialize( } // namespace details_c } // namespace rmw_iceoryx_cpp +#endif // INTERNAL__ICEORYX_DESERIALIZE_TYPESUPPORT_C_HPP_ diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_cpp.hpp b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_cpp.hpp index a8e84aa..09af8f1 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_cpp.hpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize_typesupport_cpp.hpp @@ -12,7 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#pragma once +#ifndef INTERNAL__ICEORYX_DESERIALIZE_TYPESUPPORT_CPP_HPP_ +#define INTERNAL__ICEORYX_DESERIALIZE_TYPESUPPORT_CPP_HPP_ #include #include @@ -31,45 +32,23 @@ namespace rmw_iceoryx_cpp { namespace details_cpp { - // Forward declarations -template< - class T, - uint32_t SizeT = sizeof(T) -> -const char * deserialize_element( - const char * serialized_msg, - void * ros_message_field); +template +const char * deserialize_element(const char * serialized_msg, void * ros_message_field); -template< - class T, - uint32_t SizeT = sizeof(T) -> +template const char * deserialize_array( - const char * serialized_msg, - void * ros_message_field, - uint32_t size); + const char * serialized_msg, void * ros_message_field, uint32_t size); -template< - class T, - uint32_t SizeT = sizeof(T), - class ContainerT = std::vector -> -const char * deserialize_sequence( - const char * serialized_msg, - void * ros_message_field); +template> +const char * deserialize_sequence(const char * serialized_msg, void * ros_message_field); template<> const char * deserialize_sequence( const char * serialized_msg, void * ros_message_field); -template< - class T, - uint32_t SizeT = sizeof(T) -> -const char * deserialize_element( - const char * serialized_msg, - void * ros_message_field) +template +const char * deserialize_element(const char * serialized_msg, void * ros_message_field) { T * element = reinterpret_cast(ros_message_field); memcpy(element, serialized_msg, SizeT); @@ -81,30 +60,21 @@ const char * deserialize_element( template<> const char * deserialize_element( - const char * serialized_msg, - void * ros_message_field) + const char * serialized_msg, void * ros_message_field) { return deserialize_sequence(serialized_msg, ros_message_field); } template<> const char * deserialize_element( - const char * serialized_msg, - void * ros_message_field) + const char * serialized_msg, void * ros_message_field) { return deserialize_sequence( - serialized_msg, - ros_message_field); + serialized_msg, ros_message_field); } -template< - class T, - uint32_t SizeT = sizeof(T) -> -const char * deserialize_array( - const char * serialized_msg, - void * ros_message_field, - uint32_t size) +template +const char * deserialize_array(const char * serialized_msg, void * ros_message_field, uint32_t size) { auto array = reinterpret_cast *>(ros_message_field); auto data_ptr = reinterpret_cast(array->data()); @@ -116,13 +86,8 @@ const char * deserialize_array( return serialized_msg; } -template< - class T, - uint32_t SizeT = sizeof(T), - class ContainerT = std::vector -> -const char * deserialize_sequence( - const char * serialized_msg, void * ros_message_field) +template> +const char * deserialize_sequence(const char * serialized_msg, void * ros_message_field) { uint32_t sequence_size = 0; std::tie(serialized_msg, sequence_size) = pop_sequence_size(serialized_msg); @@ -182,17 +147,15 @@ const char * deserialize_sequence( template const char * deserialize_message_field( - const rosidl_typesupport_introspection_cpp::MessageMember * member, - const char * serialized_msg, + const rosidl_typesupport_introspection_cpp::MessageMember * member, const char * serialized_msg, void * ros_message_field) { debug_log("deserializing message field %s\n", member->name_); if (!member->is_array_) { return deserialize_element(serialized_msg, ros_message_field); } else if (member->array_size_ > 0 && !member->is_upper_bound_) { - return serialized_msg = deserialize_array( - serialized_msg, ros_message_field, - member->array_size_); + return serialized_msg = + deserialize_array(serialized_msg, ros_message_field, member->array_size_); } else { return serialized_msg = deserialize_sequence(serialized_msg, ros_message_field); } @@ -200,8 +163,7 @@ const char * deserialize_message_field( } const char * deserialize( - const char * serialized_msg, - const rosidl_typesupport_introspection_cpp::MessageMembers * members, + const char * serialized_msg, const rosidl_typesupport_introspection_cpp::MessageMembers * members, void * ros_message) { for (uint32_t i = 0; i < members->member_count_; ++i) { @@ -213,9 +175,8 @@ const char * deserialize( break; case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_BYTE: case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT8: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_CHAR: case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT8: @@ -230,47 +191,38 @@ const char * deserialize( deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT16: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT16: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT32: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT32: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_INT64: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_UINT64: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_STRING: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING: - serialized_msg = deserialize_message_field( - member, serialized_msg, - ros_message_field); + serialized_msg = + deserialize_message_field(member, serialized_msg, ros_message_field); break; - case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE: - { + case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE: { auto sub_members = (const rosidl_typesupport_introspection_cpp::MessageMembers *)member->members_->data; @@ -298,8 +250,7 @@ const char * deserialize( serialized_msg = deserialize(serialized_msg, sub_members, subros_message); subros_message = static_cast(subros_message) + sub_members_size; } - } - break; + } break; default: throw std::runtime_error(std::string("unknown type") + member->name_); } @@ -309,3 +260,4 @@ const char * deserialize( } // namespace details_cpp } // namespace rmw_iceoryx_cpp +#endif // INTERNAL__ICEORYX_DESERIALIZE_TYPESUPPORT_CPP_HPP_ diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_name_conversion.cpp b/rmw_iceoryx_cpp/src/internal/iceoryx_name_conversion.cpp index 371d6fe..7ed435e 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_name_conversion.cpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_name_conversion.cpp @@ -53,8 +53,7 @@ inline std::string to_message_type(const std::string & in) } inline void extract_type( - const rosidl_message_type_support_t * type_support, - std::string & service_name, + const rosidl_message_type_support_t * type_support, std::string & service_name, std::string & event_name) { service_name = to_message_type(rmw_iceoryx_cpp::iceoryx_get_message_namespace(type_support)); @@ -63,12 +62,8 @@ inline void extract_type( namespace rmw_iceoryx_cpp { - -std::tuple -get_name_n_type_from_service_description( - const std::string & service, - const std::string & instance, - const std::string & event) +std::tuple get_name_n_type_from_service_description( + const std::string & service, const std::string & instance, const std::string & event) { // Filter out inbuilt introspection topics if (service.find(ICEORYX_INTROSPECTION_SERVICE) != std::string::npos) { @@ -90,18 +85,14 @@ get_name_n_type_from_service_description( // ARA Naming std::string service_lowercase = service; std::transform( - service_lowercase.begin(), service_lowercase.end(), - service_lowercase.begin(), ::tolower); + service_lowercase.begin(), service_lowercase.end(), service_lowercase.begin(), ::tolower); return std::make_tuple( - "/" + instance + "/" + service + "/" + event, - service_lowercase + ARA_DELIMITER + event); + "/" + instance + "/" + service + "/" + event, service_lowercase + ARA_DELIMITER + event); } -std::tuple -get_service_description_from_name_n_type( - const std::string & topic_name, - const std::string & type_name) +std::tuple get_service_description_from_name_n_type( + const std::string & topic_name, const std::string & type_name) { // Filter out inbuilt introspection topics auto position_introspection_msgs = type_name.find(ICEORYX_INTROSPECTION_MSG_PACKAGE); @@ -127,8 +118,8 @@ get_service_description_from_name_n_type( std::string topic_name_lowercase = topic_name; std::transform( - topic_name_lowercase.begin(), topic_name_lowercase.end(), - topic_name_lowercase.begin(), ::tolower); + topic_name_lowercase.begin(), topic_name_lowercase.end(), topic_name_lowercase.begin(), + ::tolower); // Find the lowercase service name in the lowercased topic name auto position_package_name = topic_name_lowercase.find(service_lowercase); @@ -146,10 +137,8 @@ get_service_description_from_name_n_type( return std::make_tuple(service, instance, event); } -iox::capro::ServiceDescription -get_iceoryx_service_description( - const std::string & topic_name, - const rosidl_message_type_support_t * type_supports) +iox::capro::ServiceDescription get_iceoryx_service_description( + const std::string & topic_name, const rosidl_message_type_support_t * type_supports) { std::string package_name; std::string type_name; diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_serialization_common.hpp b/rmw_iceoryx_cpp/src/internal/iceoryx_serialization_common.hpp index c9be35e..dfa8053 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_serialization_common.hpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_serialization_common.hpp @@ -12,15 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#pragma once +#ifndef INTERNAL__ICEORYX_SERIALIZATION_COMMON_HPP_ +#define INTERNAL__ICEORYX_SERIALIZATION_COMMON_HPP_ #include #include +#include #include namespace rmw_iceoryx_cpp { - #define DEBUG_LOG 0 static inline void debug_log(const char * format, ...) @@ -32,7 +33,7 @@ static inline void debug_log(const char * format, ...) vfprintf(stderr, format, args); va_end(args); #else - (void) format; + (void)format; #endif } @@ -64,7 +65,6 @@ namespace details_c { namespace traits { - template struct sequence_type; @@ -148,5 +148,5 @@ struct sequence_type } // namespace traits } // namespace details_c - } // namespace rmw_iceoryx_cpp +#endif // INTERNAL__ICEORYX_SERIALIZATION_COMMON_HPP_ diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp index 5e8ec70..7f190d6 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp @@ -29,16 +29,13 @@ namespace rmw_iceoryx_cpp { - void serialize( - const void * ros_message, - const rosidl_message_type_support_t * type_supports, + const void * ros_message, const rosidl_message_type_support_t * type_supports, std::vector & payload_vector) { // serialize with cpp typesupport auto ts_cpp = get_message_typesupport_handle( - type_supports, - rosidl_typesupport_introspection_cpp::typesupport_identifier); + type_supports, rosidl_typesupport_introspection_cpp::typesupport_identifier); if (ts_cpp != nullptr) { auto members = static_cast(ts_cpp->data); @@ -46,9 +43,8 @@ void serialize( } // serialize with c typesupport - auto ts_c = get_message_typesupport_handle( - type_supports, - rosidl_typesupport_introspection_c__identifier); + auto ts_c = + get_message_typesupport_handle(type_supports, rosidl_typesupport_introspection_c__identifier); if (ts_c != nullptr) { auto members = static_cast(ts_c->data); diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_c.hpp b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_c.hpp index aa82d62..6d7b85b 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_c.hpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_c.hpp @@ -12,7 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#pragma once +#ifndef INTERNAL__ICEORYX_SERIALIZE_TYPESUPPORT_C_HPP_ +#define INTERNAL__ICEORYX_SERIALIZE_TYPESUPPORT_C_HPP_ #include #include @@ -30,20 +31,11 @@ namespace rmw_iceoryx_cpp { namespace details_c { - -template< - class T, - size_t SizeT = sizeof(T) -> +template void serialize_sequence(std::vector & serialized_msg, const void * ros_message_field); -template< - class T, - size_t SizeT = sizeof(T) -> -void serialize_element( - std::vector & serialized_msg, - const char * ros_message_field) +template +void serialize_element(std::vector & serialized_msg, const char * ros_message_field) { debug_log("serializing data element of %u bytes\n", SizeT); serialized_msg.insert(serialized_msg.end(), ros_message_field, ros_message_field + SizeT); @@ -51,22 +43,16 @@ void serialize_element( template<> void serialize_element( - std::vector & serialized_msg, - const char * ros_message_field) + std::vector & serialized_msg, const char * ros_message_field) { auto string = reinterpret_cast(ros_message_field); push_sequence_size(serialized_msg, string->size); serialized_msg.insert(serialized_msg.end(), string->data, string->data + string->size); } -template< - class T, - size_t SizeT = sizeof(T) -> +template void serialize_array( - std::vector & serialized_msg, - const void * ros_message_field, - uint32_t size) + std::vector & serialized_msg, const void * ros_message_field, uint32_t size) { auto array = reinterpret_cast(ros_message_field); for (size_t i = 0; i < size; ++i) { @@ -75,10 +61,7 @@ void serialize_array( } } -template< - class T, - size_t SizeT = sizeof(T) -> +template void serialize_sequence(std::vector & serialized_msg, const void * ros_message_field) { auto sequence = @@ -106,8 +89,7 @@ void serialize_message_field( } void serialize( - const void * ros_message, - const rosidl_typesupport_introspection_c__MessageMembers * members, + const void * ros_message, const rosidl_typesupport_introspection_c__MessageMembers * members, std::vector & serialized_msg) { assert(members); @@ -154,15 +136,13 @@ void serialize( break; case ::rosidl_typesupport_introspection_c__ROS_TYPE_STRING: serialize_message_field( - member, serialized_msg, - ros_message_field); + member, serialized_msg, ros_message_field); break; - case ::rosidl_typesupport_introspection_c__ROS_TYPE_MESSAGE: - { + case ::rosidl_typesupport_introspection_c__ROS_TYPE_MESSAGE: { // Iterate recursively over the complex ROS messages auto sub_members = - static_cast(member->members_ - ->data); + static_cast( + member->members_->data); const void * subros_message = nullptr; size_t sequence_size = 0; @@ -181,7 +161,8 @@ void serialize( auto vector = reinterpret_cast(ros_message_field); // Vector size points to content of vector and returns number of bytes - // submembersize is the size of one element in the vector (it is provided by type support) + // submembersize is the size of one element in the vector + // (it is provided by type support) sequence_size = vector->size / sub_members_size; if (member->is_upper_bound_ && sequence_size > member->array_size_) { throw std::runtime_error("vector overcomes the maximum length"); @@ -197,8 +178,7 @@ void serialize( serialize(subros_message, sub_members, serialized_msg); subros_message = static_cast(subros_message) + sub_members_size; } - } - break; + } break; default: throw std::runtime_error("unknown type"); } @@ -207,3 +187,4 @@ void serialize( } // namespace details_c } // namespace rmw_iceoryx_cpp +#endif // INTERNAL__ICEORYX_SERIALIZE_TYPESUPPORT_C_HPP_ diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_cpp.hpp b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_cpp.hpp index 41bfaee..31e0e6b 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_cpp.hpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize_typesupport_cpp.hpp @@ -12,13 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#pragma once +#ifndef INTERNAL__ICEORYX_SERIALIZE_TYPESUPPORT_CPP_HPP_ +#define INTERNAL__ICEORYX_SERIALIZE_TYPESUPPORT_CPP_HPP_ -#include + +#include #include #include -#include +#include #include #include @@ -33,42 +35,20 @@ namespace rmw_iceoryx_cpp { namespace details_cpp { - // Forward declarations -template< - class T, - uint32_t SizeT = sizeof(T) -> -void serialize_element( - std::vector & serialized_msg, - const void * ros_message_field); +template +void serialize_element(std::vector & serialized_msg, const void * ros_message_field); -template< - class T, - uint32_t SizeT = sizeof(T) -> +template void serialize_element( - std::vector & serialized_msg, - const void * ros_message_field, - uint32_t size); - -template< - class T, - uint32_t SizeT = sizeof(T), - class ContainerT = std::vector -> -void serialize_sequence( - std::vector & serialized_msg, - const void * ros_message_field); + std::vector & serialized_msg, const void * ros_message_field, uint32_t size); + +template> +void serialize_sequence(std::vector & serialized_msg, const void * ros_message_field); // Implementation -template< - class T, - uint32_t SizeT = sizeof(T) -> -void serialize_element( - std::vector & serialized_msg, - const char * ros_message_field) +template +void serialize_element(std::vector & serialized_msg, const char * ros_message_field) { debug_log("serializing data element of %u bytes\n", SizeT); serialized_msg.insert(serialized_msg.end(), ros_message_field, ros_message_field + SizeT); @@ -76,28 +56,21 @@ void serialize_element( template<> void serialize_element( - std::vector & serialized_msg, - const char * ros_message_field) + std::vector & serialized_msg, const char * ros_message_field) { serialize_sequence(serialized_msg, ros_message_field); } template<> void serialize_element( - std::vector & serialized_msg, - const char * ros_message_field) + std::vector & serialized_msg, const char * ros_message_field) { serialize_sequence(serialized_msg, ros_message_field); } -template< - class T, - uint32_t SizeT = sizeof(T) -> +template void serialize_array( - std::vector & serialized_msg, - const void * ros_message_field, - uint32_t size) + std::vector & serialized_msg, const void * ros_message_field, uint32_t size) { debug_log("serializing data array of size %u\n", size); auto array = reinterpret_cast *>(ros_message_field); @@ -107,11 +80,7 @@ void serialize_array( } } -template< - class T, - uint32_t SizeT = sizeof(T), - class ContainerT = std::vector -> +template> void serialize_sequence(std::vector & serialized_msg, const void * ros_message_field) { auto sequence = reinterpret_cast(ros_message_field); @@ -128,8 +97,7 @@ void serialize_sequence(std::vector & serialized_msg, const void * ros_mes template void serialize_message_field( const rosidl_typesupport_introspection_cpp::MessageMember * member, - std::vector & serialized_msg, - const char * ros_message_field) + std::vector & serialized_msg, const char * ros_message_field) { debug_log("serializing message field %s\n", member->name_); if (!member->is_array_) { @@ -142,8 +110,7 @@ void serialize_message_field( } void serialize( - const void * ros_message, - const rosidl_typesupport_introspection_cpp::MessageMembers * members, + const void * ros_message, const rosidl_typesupport_introspection_cpp::MessageMembers * members, std::vector & serialized_msg) { assert(members); @@ -194,12 +161,11 @@ void serialize( case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_WSTRING: serialize_message_field(member, serialized_msg, ros_message_field); break; - case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE: - { + case ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE: { // Iterate recursively over the complex ROS messages auto sub_members = - static_cast(member-> - members_->data); + static_cast( + member->members_->data); const void * subros_message = nullptr; size_t sequence_size = 0; @@ -217,7 +183,8 @@ void serialize( // Cast current ros_message_field ptr as vector "definition" auto vector = reinterpret_cast *>(ros_message_field); // Vector size points to content of vector and returns number of bytes - // submembersize is the size of one element in the vector (it is provided by type support) + // submembersize is the size of one element in the vector + // (it is provided by type support) sequence_size = vector->size() / sub_members_size; if (member->is_upper_bound_ && sequence_size > member->array_size_) { throw std::runtime_error("vector overcomes the maximum length"); @@ -233,8 +200,7 @@ void serialize( serialize(subros_message, sub_members, serialized_msg); subros_message = static_cast(subros_message) + sub_members_size; } - } - break; + } break; default: throw std::runtime_error(std::string("unknown type:") + member->name_); } @@ -243,3 +209,4 @@ void serialize( } // namespace details_cpp } // namespace rmw_iceoryx_cpp +#endif // INTERNAL__ICEORYX_SERIALIZE_TYPESUPPORT_CPP_HPP_ diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_topic_names_and_types.cpp b/rmw_iceoryx_cpp/src/internal/iceoryx_topic_names_and_types.cpp index fb9ba9e..c5bd7c9 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_topic_names_and_types.cpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_topic_names_and_types.cpp @@ -29,7 +29,6 @@ namespace rmw_iceoryx_cpp { - // TODO(mphnl) refactoring, too many copies void fill_topic_containers( std::map & names_n_types_, @@ -67,8 +66,8 @@ void fill_topic_containers( if (latest_chunk_header) { const iox::roudi::PortIntrospectionFieldTopic * port_sample = - static_cast(latest_chunk_header-> - payload()); + static_cast( + latest_chunk_header->payload()); names_n_types.clear(); subscribers_topics.clear(); @@ -82,8 +81,7 @@ void fill_topic_containers( names_n_types[std::get<0>(name_and_type)] = std::get<1>(name_and_type); subscribers_topics[std::string(receiver.m_runnable.c_str())].push_back( - std::get<0>( - name_and_type)); + std::get<0>(name_and_type)); } for (auto & sender : port_sample->m_senderList) { auto name_and_type = rmw_iceoryx_cpp::get_name_n_type_from_service_description( @@ -93,8 +91,7 @@ void fill_topic_containers( names_n_types[std::get<0>(name_and_type)] = std::get<1>(name_and_type); publishers_topics[std::string(sender.m_runnable.c_str())].push_back( - std::get<0>( - name_and_type)); + std::get<0>(name_and_type)); } port_receiver.releaseChunk(latest_chunk_header); } @@ -139,8 +136,7 @@ std::map> get_nodes_and_subscribers() } std::map get_publisher_names_and_types_of_node( - const char * node_name, - const char * node_namespace) + const char * node_name, const char * node_namespace) { std::map names_n_types; std::map> subscribers_topics; @@ -160,8 +156,7 @@ std::map get_publisher_names_and_types_of_node( } std::map get_subscription_names_and_types_of_node( - const char * node_name, - const char * node_namespace) + const char * node_name, const char * node_namespace) { std::map names_n_types; std::map> subscribers_topics; @@ -189,8 +184,7 @@ rmw_ret_t fill_rmw_names_and_types( if (!iceoryx_topic_names_and_types.empty()) { rmw_ret = rmw_names_and_types_init( - rmw_topic_names_and_types, - iceoryx_topic_names_and_types.size(), allocator); + rmw_topic_names_and_types, iceoryx_topic_names_and_types.size(), allocator); if (rmw_ret != RMW_RET_OK) { return rmw_ret; } diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_type_info_introspection.cpp b/rmw_iceoryx_cpp/src/internal/iceoryx_type_info_introspection.cpp index d27a19a..fc86b1b 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_type_info_introspection.cpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_type_info_introspection.cpp @@ -127,7 +127,6 @@ bool is_fixed_size(const rosidl_typesupport_introspection_c__MessageMembers * me namespace rmw_iceoryx_cpp { - bool iceoryx_is_fixed_size(const rosidl_message_type_support_t * type_supports) { // first, try to extract cpp type support @@ -140,8 +139,8 @@ bool iceoryx_is_fixed_size(const rosidl_message_type_support_t * type_supports) } // second, try to extract c type support - auto ts_c = get_message_typesupport_handle( - type_supports, rosidl_typesupport_introspection_c__identifier); + auto ts_c = + get_message_typesupport_handle(type_supports, rosidl_typesupport_introspection_c__identifier); if (ts_c != nullptr) { auto members = static_cast(ts_c->data); @@ -164,8 +163,8 @@ size_t iceoryx_get_message_size(const rosidl_message_type_support_t * type_suppo } // second, try to extract c type support - auto ts_c = get_message_typesupport_handle( - type_supports, rosidl_typesupport_introspection_c__identifier); + auto ts_c = + get_message_typesupport_handle(type_supports, rosidl_typesupport_introspection_c__identifier); if (ts_c != nullptr) { auto members = static_cast(ts_c->data); @@ -188,8 +187,8 @@ std::string iceoryx_get_message_name(const rosidl_message_type_support_t * type_ } // second, try to extract c type support - auto ts_c = get_message_typesupport_handle( - type_supports, rosidl_typesupport_introspection_c__identifier); + auto ts_c = + get_message_typesupport_handle(type_supports, rosidl_typesupport_introspection_c__identifier); if (ts_c != nullptr) { auto members = static_cast(ts_c->data); @@ -212,8 +211,8 @@ std::string iceoryx_get_message_namespace(const rosidl_message_type_support_t * } // second, try to extract c type support - auto ts_c = get_message_typesupport_handle( - type_supports, rosidl_typesupport_introspection_c__identifier); + auto ts_c = + get_message_typesupport_handle(type_supports, rosidl_typesupport_introspection_c__identifier); if (ts_c != nullptr) { auto members = static_cast(ts_c->data); @@ -239,9 +238,7 @@ bool iceoryx_is_valid_type_support(const rosidl_message_type_support_t * type_su return false; } -void iceoryx_init_message( - const rosidl_message_type_support_t * type_supports, - void * message) +void iceoryx_init_message(const rosidl_message_type_support_t * type_supports, void * message) { // first, try to extract cpp type support auto ts_cpp = get_message_typesupport_handle( @@ -254,8 +251,8 @@ void iceoryx_init_message( } // second, try to extract c type support - auto ts_c = get_message_typesupport_handle( - type_supports, rosidl_typesupport_introspection_c__identifier); + auto ts_c = + get_message_typesupport_handle(type_supports, rosidl_typesupport_introspection_c__identifier); if (ts_c != nullptr) { auto members = static_cast(ts_c->data); @@ -267,9 +264,7 @@ void iceoryx_init_message( throw std::runtime_error("no suitable type support given"); } -void iceoryx_fini_message( - const rosidl_message_type_support_t * type_supports, - void * message) +void iceoryx_fini_message(const rosidl_message_type_support_t * type_supports, void * message) { // first, try to extract cpp type support auto ts_cpp = get_message_typesupport_handle( @@ -282,8 +277,8 @@ void iceoryx_fini_message( } // second, try to extract c type support - auto ts_c = get_message_typesupport_handle( - type_supports, rosidl_typesupport_introspection_c__identifier); + auto ts_c = + get_message_typesupport_handle(type_supports, rosidl_typesupport_introspection_c__identifier); if (ts_c != nullptr) { auto members = static_cast(ts_c->data); diff --git a/rmw_iceoryx_cpp/src/rmw_client.cpp b/rmw_iceoryx_cpp/src/rmw_client.cpp index b204ae0..4382891 100644 --- a/rmw_iceoryx_cpp/src/rmw_client.cpp +++ b/rmw_iceoryx_cpp/src/rmw_client.cpp @@ -19,14 +19,10 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_client_t * -rmw_create_client( - const rmw_node_t * node, - const rosidl_service_type_support_t * type_supports, - const char * service_name, - const rmw_qos_profile_t * qos_policies) +extern "C" { +rmw_client_t * rmw_create_client( + const rmw_node_t * node, const rosidl_service_type_support_t * type_supports, + const char * service_name, const rmw_qos_profile_t * qos_policies) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, NULL); RCUTILS_CHECK_ARGUMENT_FOR_NULL(type_supports, NULL); @@ -37,10 +33,7 @@ rmw_create_client( return NULL; } -rmw_ret_t -rmw_destroy_client( - rmw_node_t * node, - rmw_client_t * client) +rmw_ret_t rmw_destroy_client(rmw_node_t * node, rmw_client_t * client) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(client, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_compare_guids_equal.cpp b/rmw_iceoryx_cpp/src/rmw_compare_guids_equal.cpp index a8d3d9c..4adcabc 100644 --- a/rmw_iceoryx_cpp/src/rmw_compare_guids_equal.cpp +++ b/rmw_iceoryx_cpp/src/rmw_compare_guids_equal.cpp @@ -17,13 +17,8 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_ret_t -rmw_compare_gids_equal( - const rmw_gid_t * gid1, - const rmw_gid_t * gid2, - bool * result) +extern "C" { +rmw_ret_t rmw_compare_gids_equal(const rmw_gid_t * gid1, const rmw_gid_t * gid2, bool * result) { *result = false; diff --git a/rmw_iceoryx_cpp/src/rmw_count.cpp b/rmw_iceoryx_cpp/src/rmw_count.cpp index 9c87cd2..78012ee 100644 --- a/rmw_iceoryx_cpp/src/rmw_count.cpp +++ b/rmw_iceoryx_cpp/src/rmw_count.cpp @@ -18,13 +18,8 @@ #include "rmw_iceoryx_cpp/iceoryx_topic_names_and_types.hpp" -extern "C" -{ -rmw_ret_t -rmw_count_publishers( - const rmw_node_t * node, - const char * topic_name, - size_t * count) +extern "C" { +rmw_ret_t rmw_count_publishers(const rmw_node_t * node, const char * topic_name, size_t * count) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(topic_name, RMW_RET_ERROR); @@ -52,11 +47,7 @@ rmw_count_publishers( return RMW_RET_OK; } -rmw_ret_t -rmw_count_subscribers( - const rmw_node_t * node, - const char * topic_name, - size_t * count) +rmw_ret_t rmw_count_subscribers(const rmw_node_t * node, const char * topic_name, size_t * count) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(topic_name, RMW_RET_ERROR); @@ -84,10 +75,8 @@ rmw_count_subscribers( return RMW_RET_OK; } -rmw_ret_t -rmw_subscription_count_matched_publishers( - const rmw_subscription_t * subscription, - size_t * publisher_count) +rmw_ret_t rmw_subscription_count_matched_publishers( + const rmw_subscription_t * subscription, size_t * publisher_count) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher_count, RMW_RET_ERROR); @@ -114,10 +103,8 @@ rmw_subscription_count_matched_publishers( return RMW_RET_OK; } -rmw_ret_t -rmw_publisher_count_matched_subscriptions( - const rmw_publisher_t * publisher, - size_t * subscription_count) +rmw_ret_t rmw_publisher_count_matched_subscriptions( + const rmw_publisher_t * publisher, size_t * subscription_count) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription_count, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_event.cpp b/rmw_iceoryx_cpp/src/rmw_event.cpp index bed8ef2..74efe2a 100644 --- a/rmw_iceoryx_cpp/src/rmw_event.cpp +++ b/rmw_iceoryx_cpp/src/rmw_event.cpp @@ -17,31 +17,24 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_ret_t -rmw_publisher_event_init( - rmw_event_t * rmw_event, - const rmw_publisher_t * publisher, - rmw_event_type_t event_type) +extern "C" { +rmw_ret_t rmw_publisher_event_init( + rmw_event_t * rmw_event, const rmw_publisher_t * publisher, rmw_event_type_t event_type) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(rmw_event, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); - (void) event_type; + (void)event_type; RMW_SET_ERROR_MSG("rmw_iceoryx_cpp does not support publisher events."); return RMW_RET_UNSUPPORTED; } -rmw_ret_t -rmw_subscription_event_init( - rmw_event_t * rmw_event, - const rmw_subscription_t * subscription, - rmw_event_type_t event_type) +rmw_ret_t rmw_subscription_event_init( + rmw_event_t * rmw_event, const rmw_subscription_t * subscription, rmw_event_type_t event_type) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(rmw_event, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); - (void) event_type; + (void)event_type; RMW_SET_ERROR_MSG("rmw_iceoryx_cpp does not support subscription events."); return RMW_RET_UNSUPPORTED; diff --git a/rmw_iceoryx_cpp/src/rmw_get_gid_for_publisher.cpp b/rmw_iceoryx_cpp/src/rmw_get_gid_for_publisher.cpp index 0a9528a..72cb7a8 100644 --- a/rmw_iceoryx_cpp/src/rmw_get_gid_for_publisher.cpp +++ b/rmw_iceoryx_cpp/src/rmw_get_gid_for_publisher.cpp @@ -20,10 +20,8 @@ #include "./types/iceoryx_publisher.hpp" -extern "C" -{ -rmw_ret_t -rmw_get_gid_for_publisher(const rmw_publisher_t * publisher, rmw_gid_t * gid) +extern "C" { +rmw_ret_t rmw_get_gid_for_publisher(const rmw_publisher_t * publisher, rmw_gid_t * gid) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(gid, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_get_implementation_identifier.cpp b/rmw_iceoryx_cpp/src/rmw_get_implementation_identifier.cpp index bee33d7..70c28b3 100644 --- a/rmw_iceoryx_cpp/src/rmw_get_implementation_identifier.cpp +++ b/rmw_iceoryx_cpp/src/rmw_get_implementation_identifier.cpp @@ -18,11 +18,6 @@ const char * const rmw_iceoryx_cpp_identifier = "rmw_iceoryx_cpp"; -extern "C" -{ -const char * -rmw_get_implementation_identifier() -{ - return rmw_iceoryx_cpp_identifier; -} +extern "C" { +const char * rmw_get_implementation_identifier() {return rmw_iceoryx_cpp_identifier;} } // extern "C" diff --git a/rmw_iceoryx_cpp/src/rmw_get_serialization_format.cpp b/rmw_iceoryx_cpp/src/rmw_get_serialization_format.cpp index 8a3835c..f1f72a0 100644 --- a/rmw_iceoryx_cpp/src/rmw_get_serialization_format.cpp +++ b/rmw_iceoryx_cpp/src/rmw_get_serialization_format.cpp @@ -16,11 +16,6 @@ const char * const iceoryx_serialization_format = "shared_memory"; -extern "C" -{ -const char * -rmw_get_serialization_format() -{ - return iceoryx_serialization_format; -} +extern "C" { +const char * rmw_get_serialization_format() {return iceoryx_serialization_format;} } // extern "C" diff --git a/rmw_iceoryx_cpp/src/rmw_get_topic_endpoint_info.cpp b/rmw_iceoryx_cpp/src/rmw_get_topic_endpoint_info.cpp index 7bcdde0..f41459b 100644 --- a/rmw_iceoryx_cpp/src/rmw_get_topic_endpoint_info.cpp +++ b/rmw_iceoryx_cpp/src/rmw_get_topic_endpoint_info.cpp @@ -18,39 +18,30 @@ #include "rmw/rmw.h" #include "rmw/topic_endpoint_info_array.h" -extern "C" -{ -rmw_ret_t -rmw_get_publishers_info_by_topic( - const rmw_node_t * node, - rcutils_allocator_t * allocator, - const char * topic_name, - bool no_mangle, +extern "C" { +rmw_ret_t rmw_get_publishers_info_by_topic( + const rmw_node_t * node, rcutils_allocator_t * allocator, const char * topic_name, bool no_mangle, rmw_topic_endpoint_info_array_t * publishers_info) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(allocator, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(topic_name, RMW_RET_ERROR); - (void) no_mangle; - (void) publishers_info; + (void)no_mangle; + (void)publishers_info; RMW_SET_ERROR_MSG("rmw_iceoryx_cpp does not support publishers info."); return RMW_RET_UNSUPPORTED; } -rmw_ret_t -rmw_get_subscriptions_info_by_topic( - const rmw_node_t * node, - rcutils_allocator_t * allocator, - const char * topic_name, - bool no_mangle, +rmw_ret_t rmw_get_subscriptions_info_by_topic( + const rmw_node_t * node, rcutils_allocator_t * allocator, const char * topic_name, bool no_mangle, rmw_topic_endpoint_info_array_t * subscriptions_info) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(allocator, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(topic_name, RMW_RET_ERROR); - (void) no_mangle; - (void) subscriptions_info; + (void)no_mangle; + (void)subscriptions_info; RMW_SET_ERROR_MSG("rmw_iceoryx_cpp does not support subscriptions info."); return RMW_RET_UNSUPPORTED; diff --git a/rmw_iceoryx_cpp/src/rmw_guard_condition.cpp b/rmw_iceoryx_cpp/src/rmw_guard_condition.cpp index a64c6dc..8a7b31c 100644 --- a/rmw_iceoryx_cpp/src/rmw_guard_condition.cpp +++ b/rmw_iceoryx_cpp/src/rmw_guard_condition.cpp @@ -22,18 +22,14 @@ #include "./iceoryx_identifier.hpp" #include "./types/iceoryx_guard_condition.hpp" -extern "C" -{ -rmw_guard_condition_t * -rmw_create_guard_condition(rmw_context_t * context) +extern "C" { +rmw_guard_condition_t * rmw_create_guard_condition(rmw_context_t * context) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, nullptr); RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_create_guard_condition - : context, - context->implementation_identifier, - rmw_get_implementation_identifier(), + : context, context->implementation_identifier, rmw_get_implementation_identifier(), // TODO(wwjwood): replace this with RMW_RET_INCORRECT_RMW_IMPLEMENTATION when // possible return nullptr); @@ -48,17 +44,14 @@ rmw_create_guard_condition(rmw_context_t * context) } guard_condition->implementation_identifier = rmw_get_implementation_identifier(); - iceoryx_guard_condition = static_cast( - rmw_allocate(sizeof(IceoryxGuardCondition))); + iceoryx_guard_condition = + static_cast(rmw_allocate(sizeof(IceoryxGuardCondition))); if (!iceoryx_guard_condition) { RMW_SET_ERROR_MSG("failed to construct guard condition data"); goto fail; } RMW_TRY_PLACEMENT_NEW( - iceoryx_guard_condition, - iceoryx_guard_condition, - goto fail, - IceoryxGuardCondition, ) + iceoryx_guard_condition, iceoryx_guard_condition, goto fail, IceoryxGuardCondition, ) guard_condition->data = iceoryx_guard_condition; return guard_condition; @@ -76,25 +69,21 @@ rmw_create_guard_condition(rmw_context_t * context) return nullptr; } -rmw_ret_t -rmw_destroy_guard_condition(rmw_guard_condition_t * guard_condition) +rmw_ret_t rmw_destroy_guard_condition(rmw_guard_condition_t * guard_condition) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(guard_condition, RMW_RET_ERROR); RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_destroy_guard_condition - : guard_condition, - guard_condition->implementation_identifier, - rmw_get_implementation_identifier(), - return RMW_RET_ERROR); + : guard_condition, guard_condition->implementation_identifier, + rmw_get_implementation_identifier(), return RMW_RET_ERROR); auto iceoryx_guard_condition = static_cast(guard_condition->data); auto result = RMW_RET_OK; if (iceoryx_guard_condition) { RMW_TRY_DESTRUCTOR( - iceoryx_guard_condition->~IceoryxGuardCondition(), - iceoryx_guard_condition, + iceoryx_guard_condition->~IceoryxGuardCondition(), iceoryx_guard_condition, result = RMW_RET_ERROR) rmw_free(iceoryx_guard_condition); } diff --git a/rmw_iceoryx_cpp/src/rmw_init.cpp b/rmw_iceoryx_cpp/src/rmw_init.cpp index 9649161..f48f36a 100644 --- a/rmw_iceoryx_cpp/src/rmw_init.cpp +++ b/rmw_iceoryx_cpp/src/rmw_init.cpp @@ -24,10 +24,8 @@ #include "rmw/rmw.h" #include "rmw/types.h" -extern "C" -{ -rmw_ret_t -rmw_init_options_init(rmw_init_options_t * init_options, rcutils_allocator_t allocator) +extern "C" { +rmw_ret_t rmw_init_options_init(rmw_init_options_t * init_options, rcutils_allocator_t allocator) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT); RCUTILS_CHECK_ALLOCATOR(&allocator, return RMW_RET_INVALID_ARGUMENT); @@ -43,15 +41,13 @@ rmw_init_options_init(rmw_init_options_t * init_options, rcutils_allocator_t all return RMW_RET_OK; } -rmw_ret_t -rmw_init_options_copy(const rmw_init_options_t * src, rmw_init_options_t * dst) +rmw_ret_t rmw_init_options_copy(const rmw_init_options_t * src, rmw_init_options_t * dst) { RMW_CHECK_ARGUMENT_FOR_NULL(src, RMW_RET_INVALID_ARGUMENT); RMW_CHECK_ARGUMENT_FOR_NULL(dst, RMW_RET_INVALID_ARGUMENT); RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_init_options_copy - : source options, - src->implementation_identifier, + : source options, src->implementation_identifier, rmw_get_implementation_identifier(), return RMW_RET_INCORRECT_RMW_IMPLEMENTATION); if (NULL != dst->implementation_identifier) { @@ -63,30 +59,26 @@ rmw_init_options_copy(const rmw_init_options_t * src, rmw_init_options_t * dst) return RMW_RET_OK; } -rmw_ret_t -rmw_init_options_fini(rmw_init_options_t * init_options) +rmw_ret_t rmw_init_options_fini(rmw_init_options_t * init_options) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT); RCUTILS_CHECK_ALLOCATOR(&(init_options->allocator), return RMW_RET_INVALID_ARGUMENT); RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_init_options_fini - : options, - init_options->implementation_identifier, + : options, init_options->implementation_identifier, rmw_get_implementation_identifier(), return RMW_RET_INCORRECT_RMW_IMPLEMENTATION); *init_options = rmw_get_zero_initialized_init_options(); return RMW_RET_OK; } -rmw_ret_t -rmw_init(const rmw_init_options_t * options, rmw_context_t * context) +rmw_ret_t rmw_init(const rmw_init_options_t * options, rmw_context_t * context) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(options, RMW_RET_INVALID_ARGUMENT); RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT); RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_init - : options, - options->implementation_identifier, + : options, options->implementation_identifier, rmw_get_implementation_identifier(), return RMW_RET_INCORRECT_RMW_IMPLEMENTATION); context->instance_id = options->instance_id; @@ -109,28 +101,24 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) return RMW_RET_OK; } -rmw_ret_t -rmw_shutdown(rmw_context_t * context) +rmw_ret_t rmw_shutdown(rmw_context_t * context) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT); RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_shutdown - : context, - context->implementation_identifier, + : context, context->implementation_identifier, rmw_get_implementation_identifier(), return RMW_RET_INCORRECT_RMW_IMPLEMENTATION); return RMW_RET_OK; } -rmw_ret_t -rmw_context_fini(rmw_context_t * context) +rmw_ret_t rmw_context_fini(rmw_context_t * context) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, RMW_RET_INVALID_ARGUMENT); RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_context_fini - : context, - context->implementation_identifier, + : context, context->implementation_identifier, rmw_get_implementation_identifier(), return RMW_RET_INCORRECT_RMW_IMPLEMENTATION); // context impl is explicitly supposed to be nullptr for now, see rmw_init() diff --git a/rmw_iceoryx_cpp/src/rmw_logging.cpp b/rmw_iceoryx_cpp/src/rmw_logging.cpp index f3e5639..40c59bf 100644 --- a/rmw_iceoryx_cpp/src/rmw_logging.cpp +++ b/rmw_iceoryx_cpp/src/rmw_logging.cpp @@ -15,10 +15,8 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_ret_t -rmw_set_log_severity(rmw_log_severity_t severity) +extern "C" { +rmw_ret_t rmw_set_log_severity(rmw_log_severity_t severity) { (void)severity; diff --git a/rmw_iceoryx_cpp/src/rmw_node.cpp b/rmw_iceoryx_cpp/src/rmw_node.cpp index d63d507..8395450 100644 --- a/rmw_iceoryx_cpp/src/rmw_node.cpp +++ b/rmw_iceoryx_cpp/src/rmw_node.cpp @@ -20,14 +20,9 @@ #include "./types/iceoryx_node.hpp" -extern "C" -{ -rmw_node_t * -rmw_create_node( - rmw_context_t * context, - const char * name, - const char * namespace_, - size_t domain_id, +extern "C" { +rmw_node_t * rmw_create_node( + rmw_context_t * context, const char * name, const char * namespace_, size_t domain_id, bool localhost_only) { (void)domain_id; @@ -37,7 +32,6 @@ rmw_create_node( RCUTILS_CHECK_ARGUMENT_FOR_NULL(name, nullptr); RCUTILS_CHECK_ARGUMENT_FOR_NULL(namespace_, nullptr); - RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_create_node : context, context->implementation_identifier, @@ -72,20 +66,18 @@ rmw_create_node( goto fail; } RMW_TRY_PLACEMENT_NEW( - graph_change_notifier, graph_change_notifier, goto fail, - IceoryxGraphChangeNotifier, guard_condition) + graph_change_notifier, graph_change_notifier, goto fail, IceoryxGraphChangeNotifier, + guard_condition) // allocate iceoryx_runnable iceoryx_runnable = - static_cast(rmw_allocate( - sizeof(iox::runtime::Runnable))); + static_cast(rmw_allocate(sizeof(iox::runtime::Runnable))); if (!iceoryx_runnable) { RMW_SET_ERROR_MSG("failed to allocate memory for iceoryx runnable"); goto fail; } RMW_TRY_PLACEMENT_NEW( - iceoryx_runnable, iceoryx_runnable, - goto fail, iox::runtime::Runnable, + iceoryx_runnable, iceoryx_runnable, goto fail, iox::runtime::Runnable, iox::cxx::CString100(iox::cxx::TruncateToCapacity, full_name)); node_info = static_cast(rmw_allocate(sizeof(IceoryxNodeInfo))); @@ -94,8 +86,8 @@ rmw_create_node( goto fail; } RMW_TRY_PLACEMENT_NEW( - node_info, node_info, goto fail, IceoryxNodeInfo, guard_condition, - graph_change_notifier, iceoryx_runnable) + node_info, node_info, goto fail, IceoryxNodeInfo, guard_condition, graph_change_notifier, + iceoryx_runnable) node_handle->data = node_info; @@ -129,8 +121,7 @@ rmw_create_node( } } if (iceoryx_runnable) { - RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE( - iceoryx_runnable->~Runnable(), iox::runtime::Runnable) + RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE(iceoryx_runnable->~Runnable(), iox::runtime::Runnable) rmw_free(iceoryx_runnable); } if (node_info) { @@ -147,8 +138,7 @@ rmw_create_node( return nullptr; } -rmw_ret_t -rmw_destroy_node(rmw_node_t * node) +rmw_ret_t rmw_destroy_node(rmw_node_t * node) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); @@ -164,8 +154,7 @@ rmw_destroy_node(rmw_node_t * node) if (node_info->graph_change_notifier_) { RMW_TRY_DESTRUCTOR( node_info->graph_change_notifier_->~IceoryxGraphChangeNotifier(), - node_info->graph_change_notifier_, - result = RMW_RET_ERROR) + node_info->graph_change_notifier_, result = RMW_RET_ERROR) rmw_free(node_info->graph_change_notifier_); } if (RMW_RET_OK != rmw_destroy_guard_condition(node_info->guard_condition_)) { @@ -174,15 +163,11 @@ rmw_destroy_node(rmw_node_t * node) } if (node_info->iceoryx_runnable_) { RMW_TRY_DESTRUCTOR( - node_info->iceoryx_runnable_->~Runnable(), - node_info->iceoryx_runnable_, + node_info->iceoryx_runnable_->~Runnable(), node_info->iceoryx_runnable_, result = RMW_RET_ERROR) rmw_free(node_info->iceoryx_runnable_); } - RMW_TRY_DESTRUCTOR( - node_info->~IceoryxNodeInfo(), - node_info_, - result = RMW_RET_ERROR) + RMW_TRY_DESTRUCTOR(node_info->~IceoryxNodeInfo(), node_info_, result = RMW_RET_ERROR) rmw_free(node_info); } node->data = nullptr; @@ -198,8 +183,7 @@ rmw_destroy_node(rmw_node_t * node) return result; } -rmw_ret_t -rmw_node_assert_liveliness(const rmw_node_t * node) +rmw_ret_t rmw_node_assert_liveliness(const rmw_node_t * node) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); @@ -214,8 +198,7 @@ rmw_node_assert_liveliness(const rmw_node_t * node) return RMW_RET_OK; } -const rmw_guard_condition_t * -rmw_node_get_graph_guard_condition(const rmw_node_t * node) +const rmw_guard_condition_t * rmw_node_get_graph_guard_condition(const rmw_node_t * node) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, nullptr); RCUTILS_CHECK_ARGUMENT_FOR_NULL(node->data, nullptr); diff --git a/rmw_iceoryx_cpp/src/rmw_node_info_and_types.cpp b/rmw_iceoryx_cpp/src/rmw_node_info_and_types.cpp index 1256087..b2320f0 100644 --- a/rmw_iceoryx_cpp/src/rmw_node_info_and_types.cpp +++ b/rmw_iceoryx_cpp/src/rmw_node_info_and_types.cpp @@ -16,30 +16,24 @@ #include "rcutils/logging_macros.h" #include "rcutils/strdup.h" -#include "rmw/impl/cpp/macros.hpp" -#include "rmw/rmw.h" #include "rmw/get_node_info_and_types.h" +#include "rmw/impl/cpp/macros.hpp" #include "rmw/names_and_types.h" +#include "rmw/rmw.h" #include "rmw_iceoryx_cpp/iceoryx_topic_names_and_types.hpp" -extern "C" -{ -rmw_ret_t -rmw_get_subscriber_names_and_types_by_node( - const rmw_node_t * node, - rcutils_allocator_t * allocator, - const char * node_name, - const char * node_namespace, - bool no_demangle, - rmw_names_and_types_t * topic_names_and_types) +extern "C" { +rmw_ret_t rmw_get_subscriber_names_and_types_by_node( + const rmw_node_t * node, rcutils_allocator_t * allocator, const char * node_name, + const char * node_namespace, bool no_demangle, rmw_names_and_types_t * topic_names_and_types) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(allocator, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_name, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_namespace, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RMW_RET_ERROR); - (void) no_demangle; + (void)no_demangle; RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_get_subscriber_names_and_types_by_node @@ -58,21 +52,16 @@ rmw_get_subscriber_names_and_types_by_node( topic_names_and_types, iceoryx_topic_names_and_types, allocator); } -rmw_ret_t -rmw_get_publisher_names_and_types_by_node( - const rmw_node_t * node, - rcutils_allocator_t * allocator, - const char * node_name, - const char * node_namespace, - bool no_demangle, - rmw_names_and_types_t * topic_names_and_types) +rmw_ret_t rmw_get_publisher_names_and_types_by_node( + const rmw_node_t * node, rcutils_allocator_t * allocator, const char * node_name, + const char * node_namespace, bool no_demangle, rmw_names_and_types_t * topic_names_and_types) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(allocator, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_name, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_namespace, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RMW_RET_ERROR); - (void) no_demangle; + (void)no_demangle; RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_get_publisher_names_and_types_by_node @@ -91,13 +80,9 @@ rmw_get_publisher_names_and_types_by_node( topic_names_and_types, iceoryx_topic_names_and_types, allocator); } -rmw_ret_t -rmw_get_service_names_and_types_by_node( - const rmw_node_t * node, - rcutils_allocator_t * allocator, - const char * node_name, - const char * node_namespace, - rmw_names_and_types_t * service_names_and_types) +rmw_ret_t rmw_get_service_names_and_types_by_node( + const rmw_node_t * node, rcutils_allocator_t * allocator, const char * node_name, + const char * node_namespace, rmw_names_and_types_t * service_names_and_types) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(allocator, RMW_RET_ERROR); @@ -110,13 +95,9 @@ rmw_get_service_names_and_types_by_node( return RMW_RET_OK; } -rmw_ret_t -rmw_get_client_names_and_types_by_node( - const rmw_node_t * node, - rcutils_allocator_t * allocator, - const char * node_name, - const char * node_namespace, - rmw_names_and_types_t * service_names_and_types) +rmw_ret_t rmw_get_client_names_and_types_by_node( + const rmw_node_t * node, rcutils_allocator_t * allocator, const char * node_name, + const char * node_namespace, rmw_names_and_types_t * service_names_and_types) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(allocator, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_node_names.cpp b/rmw_iceoryx_cpp/src/rmw_node_names.cpp index 0c7bfef..d94da26 100644 --- a/rmw_iceoryx_cpp/src/rmw_node_names.cpp +++ b/rmw_iceoryx_cpp/src/rmw_node_names.cpp @@ -26,12 +26,9 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_ret_t -rmw_get_node_names( - const rmw_node_t * node, - rcutils_string_array_t * node_names, +extern "C" { +rmw_ret_t rmw_get_node_names( + const rmw_node_t * node, rcutils_string_array_t * node_names, rcutils_string_array_t * node_namespaces) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); @@ -72,8 +69,8 @@ rmw_get_node_names( if (latest_chunk_header) { const iox::roudi::ProcessIntrospectionFieldTopic * process_sample = - static_cast(latest_chunk_header-> - payload()); + static_cast( + latest_chunk_header->payload()); node_names_set.clear(); for (auto & process : process_sample->m_processList) { @@ -128,8 +125,8 @@ rmw_get_node_names( rcutils_ret = rcutils_string_array_fini(node_names); if (rcutils_ret != RCUTILS_RET_OK) { RCUTILS_LOG_ERROR_NAMED( - "rmw_iceoryx_cpp", - "failed to cleanup during error handling: %s", rcutils_get_error_string().str); + "rmw_iceoryx_cpp", "failed to cleanup during error handling: %s", + rcutils_get_error_string().str); rcutils_reset_error(); } } @@ -137,20 +134,17 @@ rmw_get_node_names( rcutils_ret = rcutils_string_array_fini(node_namespaces); if (rcutils_ret != RCUTILS_RET_OK) { RCUTILS_LOG_ERROR_NAMED( - "rmw_connext_cpp", - "failed to cleanup during error handling: %s", rcutils_get_error_string().str); + "rmw_connext_cpp", "failed to cleanup during error handling: %s", + rcutils_get_error_string().str); rcutils_reset_error(); } } return RMW_RET_BAD_ALLOC; } -rmw_ret_t -rmw_get_node_names_with_enclaves( - const rmw_node_t * node, - rcutils_string_array_t * node_names, - rcutils_string_array_t * node_namespaces, - rcutils_string_array_t * enclaves) +rmw_ret_t rmw_get_node_names_with_enclaves( + const rmw_node_t * node, rcutils_string_array_t * node_names, + rcutils_string_array_t * node_namespaces, rcutils_string_array_t * enclaves) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_names, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_publish.cpp b/rmw_iceoryx_cpp/src/rmw_publish.cpp index 0869168..4fb0e53 100644 --- a/rmw_iceoryx_cpp/src/rmw_publish.cpp +++ b/rmw_iceoryx_cpp/src/rmw_publish.cpp @@ -33,15 +33,11 @@ #include "./types/iceoryx_publisher.hpp" -extern "C" -{ +extern "C" { namespace details { -rmw_ret_t -send_payload( - iox::popo::Publisher * iceoryx_publisher, - const void * serialized_ros_msg, - size_t size) +rmw_ret_t send_payload( + iox::popo::Publisher * iceoryx_publisher, const void * serialized_ros_msg, size_t size) { if (serialized_ros_msg == nullptr) { RMW_SET_ERROR_MSG("serialized message pointer is null"); @@ -57,10 +53,8 @@ send_payload( } } // namespace details -rmw_ret_t -rmw_publish( - const rmw_publisher_t * publisher, - const void * ros_message, +rmw_ret_t rmw_publish( + const rmw_publisher_t * publisher, const void * ros_message, rmw_publisher_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); @@ -104,15 +98,13 @@ rmw_publish( return details::send_payload(iceoryx_sender, payload_vector.data(), payload_vector.size()); } -rmw_ret_t -rmw_publish_serialized_message( - const rmw_publisher_t * publisher, - const rmw_serialized_message_t * serialized_message, +rmw_ret_t rmw_publish_serialized_message( + const rmw_publisher_t * publisher, const rmw_serialized_message_t * serialized_message, rmw_publisher_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(serialized_message, RMW_RET_ERROR); - (void) allocation; + (void)allocation; RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_publish @@ -136,10 +128,8 @@ rmw_publish_serialized_message( iceoryx_sender, serialized_message->buffer, serialized_message->buffer_length); } -rmw_ret_t -rmw_borrow_loaned_message( - const rmw_publisher_t * publisher, - const rosidl_message_type_support_t * type_support, +rmw_ret_t rmw_borrow_loaned_message( + const rmw_publisher_t * publisher, const rosidl_message_type_support_t * type_support, void ** ros_message) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); @@ -168,15 +158,15 @@ rmw_borrow_loaned_message( return RMW_RET_ERROR; } - auto msg_memory = iceoryx_sender->allocateChunk( - static_cast(iceoryx_publisher->message_size_), true); + auto msg_memory = + iceoryx_sender->allocateChunk(static_cast(iceoryx_publisher->message_size_), true); rmw_iceoryx_cpp::iceoryx_init_message(&iceoryx_publisher->type_supports_, msg_memory); *ros_message = msg_memory; return RMW_RET_OK; } -rmw_ret_t -rmw_return_loaned_message_from_publisher(const rmw_publisher_t * publisher, void * loaned_message) +rmw_ret_t rmw_return_loaned_message_from_publisher( + const rmw_publisher_t * publisher, void * loaned_message) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(loaned_message, RMW_RET_ERROR); @@ -210,11 +200,8 @@ rmw_return_loaned_message_from_publisher(const rmw_publisher_t * publisher, void return RMW_RET_OK; } -rmw_ret_t -rmw_publish_loaned_message( - const rmw_publisher_t * publisher, - void * ros_message, - rmw_publisher_allocation_t * allocation) +rmw_ret_t rmw_publish_loaned_message( + const rmw_publisher_t * publisher, void * ros_message, rmw_publisher_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(ros_message, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_publisher.cpp b/rmw_iceoryx_cpp/src/rmw_publisher.cpp index 69bc4ca..e0076cf 100644 --- a/rmw_iceoryx_cpp/src/rmw_publisher.cpp +++ b/rmw_iceoryx_cpp/src/rmw_publisher.cpp @@ -25,13 +25,10 @@ #include "./types/iceoryx_publisher.hpp" -extern "C" -{ -rmw_ret_t -rmw_init_publisher_allocation( +extern "C" { +rmw_ret_t rmw_init_publisher_allocation( const rosidl_message_type_support_t * type_support, - const rosidl_runtime_c__Sequence__bound * message_bounds, - rmw_publisher_allocation_t * allocation) + const rosidl_runtime_c__Sequence__bound * message_bounds, rmw_publisher_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(type_support, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(message_bounds, RMW_RET_ERROR); @@ -41,8 +38,7 @@ rmw_init_publisher_allocation( return RMW_RET_UNSUPPORTED; } -rmw_ret_t -rmw_fini_publisher_allocation(rmw_publisher_allocation_t * allocation) +rmw_ret_t rmw_fini_publisher_allocation(rmw_publisher_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(allocation, RMW_RET_ERROR); @@ -50,12 +46,9 @@ rmw_fini_publisher_allocation(rmw_publisher_allocation_t * allocation) return RMW_RET_UNSUPPORTED; } -rmw_publisher_t * -rmw_create_publisher( - const rmw_node_t * node, - const rosidl_message_type_support_t * type_supports, - const char * topic_name, - const rmw_qos_profile_t * qos_policies, +rmw_publisher_t * rmw_create_publisher( + const rmw_node_t * node, const rosidl_message_type_support_t * type_supports, + const char * topic_name, const rmw_qos_profile_t * qos_policies, const rmw_publisher_options_t * publisher_options) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, nullptr); @@ -66,7 +59,8 @@ rmw_create_publisher( RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_create_publisher - : node, node->implementation_identifier, rmw_get_implementation_identifier(), return nullptr); + : node, node->implementation_identifier, + rmw_get_implementation_identifier(), return nullptr); // create the iceoryx service description for a sender auto service_description = @@ -85,30 +79,26 @@ rmw_create_publisher( } // allocate iceoryx_sender - iceoryx_sender = - static_cast(rmw_allocate( - sizeof(iox::popo::Publisher))); + iceoryx_sender = static_cast(rmw_allocate(sizeof(iox::popo::Publisher))); if (!iceoryx_sender) { RMW_SET_ERROR_MSG("failed to allocate memory for iceoryx sender"); goto fail; } RMW_TRY_PLACEMENT_NEW( - iceoryx_sender, iceoryx_sender, - goto fail, iox::popo::Publisher, service_description, + iceoryx_sender, iceoryx_sender, goto fail, iox::popo::Publisher, service_description, iox::cxx::CString100(iox::cxx::TruncateToCapacity, node_full_name)); iceoryx_sender->offer(); // make the sender visible // allocate iceoryx_publisher - iceoryx_publisher = - static_cast(rmw_allocate(sizeof(IceoryxPublisher))); + iceoryx_publisher = static_cast(rmw_allocate(sizeof(IceoryxPublisher))); if (!iceoryx_publisher) { RMW_SET_ERROR_MSG("failed to allocate memory for rmw iceoryx publisher"); goto fail; } RMW_TRY_PLACEMENT_NEW( - iceoryx_publisher, iceoryx_publisher, - goto fail, IceoryxPublisher, type_supports, iceoryx_sender); + iceoryx_publisher, iceoryx_publisher, goto fail, IceoryxPublisher, type_supports, + iceoryx_sender); // compose rmw_publisher rmw_publisher->implementation_identifier = rmw_get_implementation_identifier(); @@ -127,8 +117,7 @@ rmw_create_publisher( fail: if (rmw_publisher) { if (iceoryx_sender) { - RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE( - iceoryx_sender->~Publisher(), iox::popo::Publisher) + RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE(iceoryx_sender->~Publisher(), iox::popo::Publisher) rmw_free(iceoryx_sender); } if (iceoryx_publisher) { @@ -145,8 +134,7 @@ rmw_create_publisher( return nullptr; } -rmw_ret_t -rmw_publisher_assert_liveliness(const rmw_publisher_t * publisher) +rmw_ret_t rmw_publisher_assert_liveliness(const rmw_publisher_t * publisher) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); @@ -154,8 +142,7 @@ rmw_publisher_assert_liveliness(const rmw_publisher_t * publisher) return RMW_RET_UNSUPPORTED; } -rmw_ret_t -rmw_publisher_get_actual_qos(const rmw_publisher_t * publisher, rmw_qos_profile_t * qos) +rmw_ret_t rmw_publisher_get_actual_qos(const rmw_publisher_t * publisher, rmw_qos_profile_t * qos) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(qos, RMW_RET_ERROR); @@ -168,8 +155,7 @@ rmw_publisher_get_actual_qos(const rmw_publisher_t * publisher, rmw_qos_profile_ return RMW_RET_OK; } -rmw_ret_t -rmw_destroy_publisher(rmw_node_t * node, rmw_publisher_t * publisher) +rmw_ret_t rmw_destroy_publisher(rmw_node_t * node, rmw_publisher_t * publisher) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(publisher, RMW_RET_ERROR); @@ -185,15 +171,12 @@ rmw_destroy_publisher(rmw_node_t * node, rmw_publisher_t * publisher) if (iceoryx_publisher) { if (iceoryx_publisher->iceoryx_sender_) { RMW_TRY_DESTRUCTOR( - iceoryx_publisher->iceoryx_sender_->~Publisher(), - iceoryx_publisher->iceoryx_sender_, + iceoryx_publisher->iceoryx_sender_->~Publisher(), iceoryx_publisher->iceoryx_sender_, result = RMW_RET_ERROR) rmw_free(iceoryx_publisher->iceoryx_sender_); } RMW_TRY_DESTRUCTOR( - iceoryx_publisher->~IceoryxPublisher(), - iceoryx_publisher, - result = RMW_RET_ERROR) + iceoryx_publisher->~IceoryxPublisher(), iceoryx_publisher, result = RMW_RET_ERROR) rmw_free(iceoryx_publisher); } publisher->data = nullptr; diff --git a/rmw_iceoryx_cpp/src/rmw_request.cpp b/rmw_iceoryx_cpp/src/rmw_request.cpp index 0f77eed..844f29b 100644 --- a/rmw_iceoryx_cpp/src/rmw_request.cpp +++ b/rmw_iceoryx_cpp/src/rmw_request.cpp @@ -17,13 +17,9 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_ret_t -rmw_send_request( - const rmw_client_t * client, - const void * ros_request, - int64_t * sequence_id) +extern "C" { +rmw_ret_t rmw_send_request( + const rmw_client_t * client, const void * ros_request, int64_t * sequence_id) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(client, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(ros_request, RMW_RET_ERROR); @@ -33,11 +29,8 @@ rmw_send_request( return RMW_RET_UNSUPPORTED; } -rmw_ret_t -rmw_take_request( - const rmw_service_t * service, - rmw_service_info_t * request_header, - void * ros_request, +rmw_ret_t rmw_take_request( + const rmw_service_t * service, rmw_service_info_t * request_header, void * ros_request, bool * taken) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(service, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_response.cpp b/rmw_iceoryx_cpp/src/rmw_response.cpp index e73debe..99561aa 100644 --- a/rmw_iceoryx_cpp/src/rmw_response.cpp +++ b/rmw_iceoryx_cpp/src/rmw_response.cpp @@ -17,13 +17,9 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_ret_t -rmw_take_response( - const rmw_client_t * client, - rmw_service_info_t * request_header, - void * ros_response, +extern "C" { +rmw_ret_t rmw_take_response( + const rmw_client_t * client, rmw_service_info_t * request_header, void * ros_response, bool * taken) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(client, RMW_RET_ERROR); @@ -35,11 +31,8 @@ rmw_take_response( return RMW_RET_UNSUPPORTED; } -rmw_ret_t -rmw_send_response( - const rmw_service_t * service, - rmw_request_id_t * request_header, - void * ros_response) +rmw_ret_t rmw_send_response( + const rmw_service_t * service, rmw_request_id_t * request_header, void * ros_response) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(service, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(request_header, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_serialize.cpp b/rmw_iceoryx_cpp/src/rmw_serialize.cpp index 5297650..4b3bb44 100644 --- a/rmw_iceoryx_cpp/src/rmw_serialize.cpp +++ b/rmw_iceoryx_cpp/src/rmw_serialize.cpp @@ -28,11 +28,8 @@ namespace details { -rmw_ret_t -copy_payload_into_serialized_message( - rmw_serialized_message_t * serialized_message, - const void * payload, - size_t payload_size) +rmw_ret_t copy_payload_into_serialized_message( + rmw_serialized_message_t * serialized_message, const void * payload, size_t payload_size) { auto ret = rmw_serialized_message_resize(serialized_message, payload_size); if (RMW_RET_OK == ret) { @@ -43,12 +40,9 @@ copy_payload_into_serialized_message( } } // namespace details -extern "C" -{ -rmw_ret_t -rmw_serialize( - const void * ros_message, - const rosidl_message_type_support_t * type_supports, +extern "C" { +rmw_ret_t rmw_serialize( + const void * ros_message, const rosidl_message_type_support_t * type_supports, rmw_serialized_message_t * serialized_message) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(ros_message, RMW_RET_ERROR); @@ -69,11 +63,9 @@ rmw_serialize( serialized_message, payload_vector.data(), payload_vector.size()); } -rmw_ret_t -rmw_deserialize( +rmw_ret_t rmw_deserialize( const rmw_serialized_message_t * serialized_message, - const rosidl_message_type_support_t * type_supports, - void * ros_message) + const rosidl_message_type_support_t * type_supports, void * ros_message) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(serialized_message, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(type_supports, RMW_RET_ERROR); @@ -91,11 +83,9 @@ rmw_deserialize( return RMW_RET_OK; } -rmw_ret_t -rmw_get_serialized_message_size( +rmw_ret_t rmw_get_serialized_message_size( const rosidl_message_type_support_t * type_supports, - const rosidl_runtime_c__Sequence__bound * message_bounds, - size_t * size) + const rosidl_runtime_c__Sequence__bound * message_bounds, size_t * size) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(type_supports, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(message_bounds, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_service.cpp b/rmw_iceoryx_cpp/src/rmw_service.cpp index f26a16a..642c101 100644 --- a/rmw_iceoryx_cpp/src/rmw_service.cpp +++ b/rmw_iceoryx_cpp/src/rmw_service.cpp @@ -18,14 +18,10 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_service_t * -rmw_create_service( - const rmw_node_t * node, - const rosidl_service_type_support_t * type_supports, - const char * service_name, - const rmw_qos_profile_t * qos_policies) +extern "C" { +rmw_service_t * rmw_create_service( + const rmw_node_t * node, const rosidl_service_type_support_t * type_supports, + const char * service_name, const rmw_qos_profile_t * qos_policies) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, nullptr); RCUTILS_CHECK_ARGUMENT_FOR_NULL(type_supports, nullptr); @@ -58,8 +54,7 @@ rmw_create_service( return rmw_service; } -rmw_ret_t -rmw_destroy_service(rmw_node_t * node, rmw_service_t * service) +rmw_ret_t rmw_destroy_service(rmw_node_t * node, rmw_service_t * service) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(service, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_service_names_and_types.cpp b/rmw_iceoryx_cpp/src/rmw_service_names_and_types.cpp index 8463144..3009815 100644 --- a/rmw_iceoryx_cpp/src/rmw_service_names_and_types.cpp +++ b/rmw_iceoryx_cpp/src/rmw_service_names_and_types.cpp @@ -19,12 +19,9 @@ #include "rmw/names_and_types.h" #include "rmw/rmw.h" -extern "C" -{ -rmw_ret_t -rmw_get_service_names_and_types( - const rmw_node_t * node, - rcutils_allocator_t * allocator, +extern "C" { +rmw_ret_t rmw_get_service_names_and_types( + const rmw_node_t * node, rcutils_allocator_t * allocator, rmw_names_and_types_t * service_names_and_types) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_service_server_is_available.cpp b/rmw_iceoryx_cpp/src/rmw_service_server_is_available.cpp index 74663ba..6cad9d9 100644 --- a/rmw_iceoryx_cpp/src/rmw_service_server_is_available.cpp +++ b/rmw_iceoryx_cpp/src/rmw_service_server_is_available.cpp @@ -17,13 +17,9 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_ret_t -rmw_service_server_is_available( - const rmw_node_t * node, - const rmw_client_t * client, - bool * is_available) +extern "C" { +rmw_ret_t rmw_service_server_is_available( + const rmw_node_t * node, const rmw_client_t * client, bool * is_available) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(client, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_subscription.cpp b/rmw_iceoryx_cpp/src/rmw_subscription.cpp index 83c873c..19d156b 100644 --- a/rmw_iceoryx_cpp/src/rmw_subscription.cpp +++ b/rmw_iceoryx_cpp/src/rmw_subscription.cpp @@ -26,10 +26,8 @@ #include "./types/iceoryx_subscription.hpp" -extern "C" -{ -rmw_ret_t -rmw_init_subscription_allocation( +extern "C" { +rmw_ret_t rmw_init_subscription_allocation( const rosidl_message_type_support_t * type_supports, const rosidl_runtime_c__Sequence__bound * message_bounds, rmw_subscription_allocation_t * allocation) @@ -42,8 +40,7 @@ rmw_init_subscription_allocation( return RMW_RET_UNSUPPORTED; } -rmw_ret_t -rmw_fini_subscription_allocation(rmw_subscription_allocation_t * allocation) +rmw_ret_t rmw_fini_subscription_allocation(rmw_subscription_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(allocation, RMW_RET_ERROR); @@ -51,12 +48,9 @@ rmw_fini_subscription_allocation(rmw_subscription_allocation_t * allocation) return RMW_RET_UNSUPPORTED; } -rmw_subscription_t * -rmw_create_subscription( - const rmw_node_t * node, - const rosidl_message_type_support_t * type_supports, - const char * topic_name, - const rmw_qos_profile_t * qos_policies, +rmw_subscription_t * rmw_create_subscription( + const rmw_node_t * node, const rosidl_message_type_support_t * type_supports, + const char * topic_name, const rmw_qos_profile_t * qos_policies, const rmw_subscription_options_t * subscription_options) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, nullptr); @@ -67,7 +61,8 @@ rmw_create_subscription( RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_create_subscription - : node, node->implementation_identifier, rmw_get_implementation_identifier(), return nullptr); + : node, node->implementation_identifier, + rmw_get_implementation_identifier(), return nullptr); // create the iceoryx service description for a receiver auto service_description = @@ -85,15 +80,13 @@ rmw_create_subscription( } iceoryx_receiver = - static_cast(rmw_allocate( - sizeof(iox::popo::Subscriber))); + static_cast(rmw_allocate(sizeof(iox::popo::Subscriber))); if (!iceoryx_receiver) { RMW_SET_ERROR_MSG("failed to allocate memory for iceoryx receiver"); goto fail; } RMW_TRY_PLACEMENT_NEW( - iceoryx_receiver, iceoryx_receiver, goto fail, - iox::popo::Subscriber, service_description, + iceoryx_receiver, iceoryx_receiver, goto fail, iox::popo::Subscriber, service_description, iox::cxx::CString100(iox::cxx::TruncateToCapacity, node_full_name)) // instant subscribe, queue size form qos settings iceoryx_receiver->subscribe(qos_policies->depth); @@ -105,8 +98,8 @@ rmw_create_subscription( goto fail; } RMW_TRY_PLACEMENT_NEW( - iceoryx_subscription, iceoryx_subscription, - goto fail, IceoryxSubscription, type_supports, iceoryx_receiver) + iceoryx_subscription, iceoryx_subscription, goto fail, IceoryxSubscription, type_supports, + iceoryx_receiver) rmw_subscription->implementation_identifier = rmw_get_implementation_identifier(); rmw_subscription->data = iceoryx_subscription; @@ -125,8 +118,7 @@ rmw_create_subscription( fail: if (rmw_subscription) { if (iceoryx_receiver) { - RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE( - iceoryx_receiver->~Subscriber(), iox::popo::Subscriber) + RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE(iceoryx_receiver->~Subscriber(), iox::popo::Subscriber) rmw_free(iceoryx_receiver); } if (iceoryx_subscription) { @@ -143,10 +135,8 @@ rmw_create_subscription( return nullptr; } -rmw_ret_t -rmw_subscription_get_actual_qos( - const rmw_subscription_t * subscription, - rmw_qos_profile_t * qos) +rmw_ret_t rmw_subscription_get_actual_qos( + const rmw_subscription_t * subscription, rmw_qos_profile_t * qos) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(qos, RMW_RET_ERROR); @@ -157,10 +147,7 @@ rmw_subscription_get_actual_qos( return RMW_RET_OK; } -rmw_ret_t -rmw_destroy_subscription( - rmw_node_t * node, - rmw_subscription_t * subscription) +rmw_ret_t rmw_destroy_subscription(rmw_node_t * node, rmw_subscription_t * subscription) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); @@ -178,14 +165,11 @@ rmw_destroy_subscription( if (iceoryx_subscription->iceoryx_receiver_) { RMW_TRY_DESTRUCTOR( iceoryx_subscription->iceoryx_receiver_->~Subscriber(), - iceoryx_subscription->iceoryx_receiver_, - result = RMW_RET_ERROR) + iceoryx_subscription->iceoryx_receiver_, result = RMW_RET_ERROR) rmw_free(iceoryx_subscription->iceoryx_receiver_); } RMW_TRY_DESTRUCTOR( - iceoryx_subscription->~IceoryxSubscription(), - iceoryx_subscription, - result = RMW_RET_ERROR) + iceoryx_subscription->~IceoryxSubscription(), iceoryx_subscription, result = RMW_RET_ERROR) rmw_free(iceoryx_subscription); } subscription->data = nullptr; diff --git a/rmw_iceoryx_cpp/src/rmw_take.cpp b/rmw_iceoryx_cpp/src/rmw_take.cpp index 5aa4cf4..7b895f6 100644 --- a/rmw_iceoryx_cpp/src/rmw_take.cpp +++ b/rmw_iceoryx_cpp/src/rmw_take.cpp @@ -23,8 +23,8 @@ #include "rmw/rmw.h" #include "rmw/types.h" -#include "rmw_iceoryx_cpp/iceoryx_type_info_introspection.hpp" #include "rmw_iceoryx_cpp/iceoryx_deserialize.hpp" +#include "rmw_iceoryx_cpp/iceoryx_type_info_introspection.hpp" #include "rosidl_typesupport_cpp/message_type_support.hpp" #include "rosidl_typesupport_introspection_c/identifier.h" @@ -32,13 +32,9 @@ #include "rosidl_typesupport_introspection_cpp/identifier.hpp" #include "rosidl_typesupport_introspection_cpp/message_introspection.hpp" -extern "C" -{ -rmw_ret_t -rmw_take( - const rmw_subscription_t * subscription, - void * ros_message, - bool * taken, +extern "C" { +rmw_ret_t rmw_take( + const rmw_subscription_t * subscription, void * ros_message, bool * taken, rmw_subscription_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); @@ -48,10 +44,8 @@ rmw_take( RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_take - : subscription, - subscription->implementation_identifier, - rmw_get_implementation_identifier(), - return RMW_RET_ERROR); + : subscription, subscription->implementation_identifier, + rmw_get_implementation_identifier(), return RMW_RET_ERROR); auto iceoryx_subscription = static_cast(subscription->data); if (!iceoryx_subscription) { @@ -91,8 +85,7 @@ rmw_take( } rmw_iceoryx_cpp::deserialize( - static_cast(chunk_header->payload()), - &iceoryx_subscription->type_supports_, + static_cast(chunk_header->payload()), &iceoryx_subscription->type_supports_, ros_message); iceoryx_receiver->releaseChunk(chunk_header); *taken = true; @@ -100,13 +93,9 @@ rmw_take( return RMW_RET_OK; } -rmw_ret_t -rmw_take_with_info( - const rmw_subscription_t * subscription, - void * ros_message, - bool * taken, - rmw_message_info_t * message_info, - rmw_subscription_allocation_t * allocation) +rmw_ret_t rmw_take_with_info( + const rmw_subscription_t * subscription, void * ros_message, bool * taken, + rmw_message_info_t * message_info, rmw_subscription_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(ros_message, RMW_RET_ERROR); @@ -119,12 +108,9 @@ rmw_take_with_info( return rmw_take(subscription, ros_message, taken, allocation); } -rmw_ret_t -rmw_take_serialized_message( - const rmw_subscription_t * subscription, - rmw_serialized_message_t * serialized_message, - bool * taken, - rmw_subscription_allocation_t * allocation) +rmw_ret_t rmw_take_serialized_message( + const rmw_subscription_t * subscription, rmw_serialized_message_t * serialized_message, + bool * taken, rmw_subscription_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(serialized_message, RMW_RET_ERROR); @@ -133,10 +119,8 @@ rmw_take_serialized_message( RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_take - : subscription, - subscription->implementation_identifier, - rmw_get_implementation_identifier(), - return RMW_RET_ERROR); + : subscription, subscription->implementation_identifier, + rmw_get_implementation_identifier(), return RMW_RET_ERROR); auto iceoryx_subscription = static_cast(subscription->data); if (!iceoryx_subscription) { @@ -179,13 +163,9 @@ rmw_take_serialized_message( return ret; } -rmw_ret_t -rmw_take_serialized_message_with_info( - const rmw_subscription_t * subscription, - rmw_serialized_message_t * serialized_message, - bool * taken, - rmw_message_info_t * message_info, - rmw_subscription_allocation_t * allocation) +rmw_ret_t rmw_take_serialized_message_with_info( + const rmw_subscription_t * subscription, rmw_serialized_message_t * serialized_message, + bool * taken, rmw_message_info_t * message_info, rmw_subscription_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(serialized_message, RMW_RET_ERROR); @@ -194,15 +174,12 @@ rmw_take_serialized_message_with_info( (void)allocation; // TODO(mphnl) implement message_info related stuff - (void) message_info; + (void)message_info; return rmw_take_serialized_message(subscription, serialized_message, taken, allocation); } -rmw_ret_t -rmw_take_loaned_message( - const rmw_subscription_t * subscription, - void ** loaned_message, - bool * taken, +rmw_ret_t rmw_take_loaned_message( + const rmw_subscription_t * subscription, void ** loaned_message, bool * taken, rmw_subscription_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); @@ -214,10 +191,8 @@ rmw_take_loaned_message( RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_take - : subscription, - subscription->implementation_identifier, - rmw_get_implementation_identifier(), - return RMW_RET_ERROR); + : subscription, subscription->implementation_identifier, + rmw_get_implementation_identifier(), return RMW_RET_ERROR); auto iceoryx_subscription = static_cast(subscription->data); if (!iceoryx_subscription) { @@ -252,20 +227,15 @@ rmw_take_loaned_message( return RMW_RET_OK; } -rmw_ret_t -rmw_take_loaned_message_with_info( - const rmw_subscription_t * subscription, - void ** loaned_message, - bool * taken, - rmw_message_info_t * message_info, - rmw_subscription_allocation_t * allocation) +rmw_ret_t rmw_take_loaned_message_with_info( + const rmw_subscription_t * subscription, void ** loaned_message, bool * taken, + rmw_message_info_t * message_info, rmw_subscription_allocation_t * allocation) { - (void) message_info; + (void)message_info; return rmw_take_loaned_message(subscription, loaned_message, taken, allocation); } -rmw_ret_t -rmw_return_loaned_message_from_subscription( +rmw_ret_t rmw_return_loaned_message_from_subscription( const rmw_subscription_t * subscription, void * loaned_message) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); @@ -273,10 +243,8 @@ rmw_return_loaned_message_from_subscription( RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_take - : subscription, - subscription->implementation_identifier, - rmw_get_implementation_identifier(), - return RMW_RET_ERROR); + : subscription, subscription->implementation_identifier, + rmw_get_implementation_identifier(), return RMW_RET_ERROR); auto iceoryx_subscription = static_cast(subscription->data); if (!iceoryx_subscription) { @@ -294,8 +262,7 @@ rmw_return_loaned_message_from_subscription( return ret ? RMW_RET_OK : RMW_RET_ERROR; } -rmw_ret_t -rmw_take_event(const rmw_event_t * event_handle, void * event_info, bool * taken) +rmw_ret_t rmw_take_event(const rmw_event_t * event_handle, void * event_info, bool * taken) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(event_handle, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(event_info, RMW_RET_ERROR); @@ -305,17 +272,13 @@ rmw_take_event(const rmw_event_t * event_handle, void * event_info, bool * taken return RMW_RET_UNSUPPORTED; } -rmw_ret_t -rmw_take_sequence( - const rmw_subscription_t * subscription, - size_t count, - rmw_message_sequence_t * message_sequence, - rmw_message_info_sequence_t * message_info_sequence, - size_t * taken, +rmw_ret_t rmw_take_sequence( + const rmw_subscription_t * subscription, size_t count, rmw_message_sequence_t * message_sequence, + rmw_message_info_sequence_t * message_info_sequence, size_t * taken, rmw_subscription_allocation_t * allocation) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); - (void) count; + (void)count; RCUTILS_CHECK_ARGUMENT_FOR_NULL(message_sequence, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(message_info_sequence, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(taken, RMW_RET_ERROR); diff --git a/rmw_iceoryx_cpp/src/rmw_topic_names_and_types.cpp b/rmw_iceoryx_cpp/src/rmw_topic_names_and_types.cpp index 159c9ca..0d95212 100644 --- a/rmw_iceoryx_cpp/src/rmw_topic_names_and_types.cpp +++ b/rmw_iceoryx_cpp/src/rmw_topic_names_and_types.cpp @@ -19,26 +19,22 @@ #include "rcutils/strdup.h" #include "rcutils/types.h" -#include "rmw/impl/cpp/macros.hpp" #include "rmw/get_topic_names_and_types.h" +#include "rmw/impl/cpp/macros.hpp" #include "rmw/names_and_types.h" #include "rmw/rmw.h" #include "rmw_iceoryx_cpp/iceoryx_topic_names_and_types.hpp" -extern "C" -{ -rmw_ret_t -rmw_get_topic_names_and_types( - const rmw_node_t * node, - rcutils_allocator_t * allocator, - bool no_demangle, +extern "C" { +rmw_ret_t rmw_get_topic_names_and_types( + const rmw_node_t * node, rcutils_allocator_t * allocator, bool no_demangle, rmw_names_and_types_t * topic_names_and_types) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(node, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(allocator, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RMW_RET_ERROR); - (void) no_demangle; + (void)no_demangle; RMW_CHECK_TYPE_IDENTIFIERS_MATCH( rmw_get_topic_names_and_types diff --git a/rmw_iceoryx_cpp/src/rmw_trigger_guard_condition.cpp b/rmw_iceoryx_cpp/src/rmw_trigger_guard_condition.cpp index f84e02c..391d894 100644 --- a/rmw_iceoryx_cpp/src/rmw_trigger_guard_condition.cpp +++ b/rmw_iceoryx_cpp/src/rmw_trigger_guard_condition.cpp @@ -19,10 +19,8 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_ret_t -rmw_trigger_guard_condition(const rmw_guard_condition_t * guard_condition_handle) +extern "C" { +rmw_ret_t rmw_trigger_guard_condition(const rmw_guard_condition_t * guard_condition_handle) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(guard_condition_handle, RMW_RET_ERROR); @@ -30,8 +28,7 @@ rmw_trigger_guard_condition(const rmw_guard_condition_t * guard_condition_handle rmw_trigger_guard_condition : guard_condition_handle, guard_condition_handle->implementation_identifier, - rmw_get_implementation_identifier(), - return RMW_RET_ERROR); + rmw_get_implementation_identifier(), return RMW_RET_ERROR); auto guard_condition = static_cast(guard_condition_handle->data); if (!guard_condition) { diff --git a/rmw_iceoryx_cpp/src/rmw_wait.cpp b/rmw_iceoryx_cpp/src/rmw_wait.cpp index fec9ec9..767c7a8 100644 --- a/rmw_iceoryx_cpp/src/rmw_wait.cpp +++ b/rmw_iceoryx_cpp/src/rmw_wait.cpp @@ -25,17 +25,11 @@ #include "./types/iceoryx_subscription.hpp" #include "./types/iceoryx_wait_set.hpp" -extern "C" -{ -rmw_ret_t -rmw_wait( - rmw_subscriptions_t * subscriptions, - rmw_guard_conditions_t * guard_conditions, - rmw_services_t * services, - rmw_clients_t * clients, - rmw_events_t * events, - rmw_wait_set_t * wait_set, - const rmw_time_t * wait_timeout) +extern "C" { +rmw_ret_t rmw_wait( + rmw_subscriptions_t * subscriptions, rmw_guard_conditions_t * guard_conditions, + rmw_services_t * services, rmw_clients_t * clients, rmw_events_t * events, + rmw_wait_set_t * wait_set, const rmw_time_t * wait_timeout) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscriptions, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(guard_conditions, RMW_RET_ERROR); @@ -118,7 +112,6 @@ rmw_wait( after_wait: - // reset all the subscriptions that don't have new data for (size_t i = 0; i < subscriptions->subscriber_count; ++i) { auto iceoryx_subscription = diff --git a/rmw_iceoryx_cpp/src/rmw_wait_set.cpp b/rmw_iceoryx_cpp/src/rmw_wait_set.cpp index 07067d5..d343133 100644 --- a/rmw_iceoryx_cpp/src/rmw_wait_set.cpp +++ b/rmw_iceoryx_cpp/src/rmw_wait_set.cpp @@ -22,10 +22,8 @@ #include "rmw/impl/cpp/macros.hpp" #include "rmw/rmw.h" -extern "C" -{ -rmw_wait_set_t * -rmw_create_wait_set(rmw_context_t * context, size_t max_conditions) +extern "C" { +rmw_wait_set_t * rmw_create_wait_set(rmw_context_t * context, size_t max_conditions) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, nullptr); (void)max_conditions; @@ -50,17 +48,14 @@ rmw_create_wait_set(rmw_context_t * context, size_t max_conditions) rmw_wait_set->implementation_identifier = rmw_get_implementation_identifier(); - process_receiver = static_cast( - rmw_allocate(sizeof(iox::popo::Subscriber))); + process_receiver = + static_cast(rmw_allocate(sizeof(iox::popo::Subscriber))); if (!process_receiver) { RMW_SET_ERROR_MSG("failed to allocate memory for wait_set data"); goto fail; } RMW_TRY_PLACEMENT_NEW( - process_receiver, - process_receiver, - goto fail, - iox::popo::Subscriber, + process_receiver, process_receiver, goto fail, iox::popo::Subscriber, iox::roudi::IntrospectionProcessService) semaphore = process_receiver->getSemaphore(); @@ -83,15 +78,12 @@ rmw_create_wait_set(rmw_context_t * context, size_t max_conditions) fail: if (rmw_wait_set) { if (process_receiver) { - RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE( - process_receiver->~Subscriber(), - iox::popo::Subscriber) + RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE(process_receiver->~Subscriber(), iox::popo::Subscriber) rmw_free(process_receiver); } if (iceoryx_wait_set) { - RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE( - iceoryx_wait_set->~IceoryxWaitSet(), IceoryxWaitSet) + RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE(iceoryx_wait_set->~IceoryxWaitSet(), IceoryxWaitSet) rmw_free(iceoryx_wait_set); } @@ -100,8 +92,7 @@ rmw_create_wait_set(rmw_context_t * context, size_t max_conditions) return nullptr; } -rmw_ret_t -rmw_destroy_wait_set(rmw_wait_set_t * wait_set) +rmw_ret_t rmw_destroy_wait_set(rmw_wait_set_t * wait_set) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(wait_set, RMW_RET_ERROR); @@ -116,8 +107,7 @@ rmw_destroy_wait_set(rmw_wait_set_t * wait_set) if (iceoryx_wait_set) { if (iceoryx_wait_set->iceoryx_receiver_) { RMW_TRY_DESTRUCTOR( - iceoryx_wait_set->iceoryx_receiver_->~Subscriber(), - iceoryx_wait_set->iceoryx_receiver_, + iceoryx_wait_set->iceoryx_receiver_->~Subscriber(), iceoryx_wait_set->iceoryx_receiver_, result = RMW_RET_ERROR) rmw_free(iceoryx_wait_set->iceoryx_receiver_); } diff --git a/rmw_iceoryx_cpp/src/types/iceoryx_guard_condition.hpp b/rmw_iceoryx_cpp/src/types/iceoryx_guard_condition.hpp index 6f58cb9..2cac9b5 100644 --- a/rmw_iceoryx_cpp/src/types/iceoryx_guard_condition.hpp +++ b/rmw_iceoryx_cpp/src/types/iceoryx_guard_condition.hpp @@ -26,8 +26,7 @@ class IceoryxGuardCondition IceoryxGuardCondition() : semaphore_(nullptr), triggered_(false) {} - void - trigger() + void trigger() { { std::lock_guard lock(mutex_); @@ -39,30 +38,21 @@ class IceoryxGuardCondition triggered_.store(true, std::memory_order_relaxed); } - void - attachSemaphore(iox::posix::Semaphore * const semaphore) + void attachSemaphore(iox::posix::Semaphore * const semaphore) { std::lock_guard lock(mutex_); semaphore_ = semaphore; } - void - detachSemaphore() + void detachSemaphore() { std::lock_guard lock(mutex_); semaphore_ = nullptr; } - bool - hasTriggered() - { - return triggered_.load(std::memory_order_relaxed); - } + bool hasTriggered() {return triggered_.load(std::memory_order_relaxed);} - void resetTriggerIndication() - { - triggered_.store(false, std::memory_order_relaxed); - } + void resetTriggerIndication() {triggered_.store(false, std::memory_order_relaxed);} private: std::mutex mutex_; diff --git a/rmw_iceoryx_cpp/src/types/iceoryx_node.hpp b/rmw_iceoryx_cpp/src/types/iceoryx_node.hpp index 2fd5fa3..57e4eb3 100644 --- a/rmw_iceoryx_cpp/src/types/iceoryx_node.hpp +++ b/rmw_iceoryx_cpp/src/types/iceoryx_node.hpp @@ -46,10 +46,8 @@ class IceoryxGraphChangeNotifier iceoryx_guard_condition_ = static_cast(guard_condition->data); RMW_CHECK_TYPE_IDENTIFIERS_MATCH( IceoryxGraphChangeNotifier - : guard_condition, - guard_condition->implementation_identifier, - rmw_get_implementation_identifier(), - iceoryx_guard_condition_ = nullptr); + : guard_condition, guard_condition->implementation_identifier, + rmw_get_implementation_identifier(), iceoryx_guard_condition_ = nullptr); } // subscribe with a callback for changes in the iceoryx graph @@ -79,8 +77,7 @@ class IceoryxGraphChangeNotifier struct IceoryxNodeInfo { IceoryxNodeInfo( - rmw_guard_condition_t * guard_condition, - IceoryxGraphChangeNotifier * graph_change_notifier, + rmw_guard_condition_t * guard_condition, IceoryxGraphChangeNotifier * graph_change_notifier, iox::runtime::Runnable * iceoryx_runnable) : guard_condition_(guard_condition), graph_change_notifier_(graph_change_notifier), diff --git a/rmw_iceoryx_cpp/src/types/iceoryx_publisher.hpp b/rmw_iceoryx_cpp/src/types/iceoryx_publisher.hpp index 225a5c5..b3fec9b 100644 --- a/rmw_iceoryx_cpp/src/types/iceoryx_publisher.hpp +++ b/rmw_iceoryx_cpp/src/types/iceoryx_publisher.hpp @@ -34,7 +34,8 @@ struct IceoryxPublisher gid_(generate_gid()), is_fixed_size_(rmw_iceoryx_cpp::iceoryx_is_fixed_size(type_supports)), message_size_(rmw_iceoryx_cpp::iceoryx_get_message_size(type_supports)) - {} + { + } rosidl_message_type_support_t type_supports_; iox::popo::Publisher * const iceoryx_sender_; diff --git a/rmw_iceoryx_cpp/src/types/iceoryx_subscription.hpp b/rmw_iceoryx_cpp/src/types/iceoryx_subscription.hpp index 67641c6..51bab34 100644 --- a/rmw_iceoryx_cpp/src/types/iceoryx_subscription.hpp +++ b/rmw_iceoryx_cpp/src/types/iceoryx_subscription.hpp @@ -31,7 +31,8 @@ struct IceoryxSubscription iceoryx_receiver_(iceoryx_receiver), is_fixed_size_(rmw_iceoryx_cpp::iceoryx_is_fixed_size(type_supports)), message_size_(rmw_iceoryx_cpp::iceoryx_get_message_size(type_supports)) - {} + { + } rosidl_message_type_support_t type_supports_; iox::popo::Subscriber * const iceoryx_receiver_; diff --git a/rmw_iceoryx_cpp/src/types/iceoryx_wait_set.hpp b/rmw_iceoryx_cpp/src/types/iceoryx_wait_set.hpp index 7c4f8f7..5e4ca76 100644 --- a/rmw_iceoryx_cpp/src/types/iceoryx_wait_set.hpp +++ b/rmw_iceoryx_cpp/src/types/iceoryx_wait_set.hpp @@ -24,10 +24,10 @@ struct IceoryxWaitSet { IceoryxWaitSet( - iox::posix::Semaphore * const semaphore, - iox::popo::Subscriber * const iceoryx_receiver) + iox::posix::Semaphore * const semaphore, iox::popo::Subscriber * const iceoryx_receiver) : semaphore_(semaphore), iceoryx_receiver_(iceoryx_receiver) - {} + { + } iox::posix::Semaphore * const semaphore_; iox::popo::Subscriber * const iceoryx_receiver_; diff --git a/rmw_iceoryx_cpp/test/iceoryx_name_conversion_test.cpp b/rmw_iceoryx_cpp/test/iceoryx_name_conversion_test.cpp index 70395d4..a187ea9 100644 --- a/rmw_iceoryx_cpp/test/iceoryx_name_conversion_test.cpp +++ b/rmw_iceoryx_cpp/test/iceoryx_name_conversion_test.cpp @@ -22,10 +22,8 @@ TEST(NameConverisonTests, get_name_n_type_from_service_description) { - auto topic_and_type = rmw_iceoryx_cpp::get_name_n_type_from_service_description( - "SERVICE", - "INSTANCE", - "EVENT"); + auto topic_and_type = + rmw_iceoryx_cpp::get_name_n_type_from_service_description("SERVICE", "INSTANCE", "EVENT"); EXPECT_EQ("/INSTANCE/SERVICE/EVENT", std::get<0>(topic_and_type)); EXPECT_EQ("service_ara_msgs/msg/EVENT", std::get<1>(topic_and_type)); } @@ -33,8 +31,7 @@ TEST(NameConverisonTests, get_name_n_type_from_service_description) TEST(NameConverisonTests, get_service_description_from_name_n_type_revers) { auto service_description = rmw_iceoryx_cpp::get_service_description_from_name_n_type( - "/INSTANCE/SERVICE/EVENT", - "service_ara_msgs/msg/EVENT"); + "/INSTANCE/SERVICE/EVENT", "service_ara_msgs/msg/EVENT"); EXPECT_EQ("SERVICE", std::get<0>(service_description)); EXPECT_EQ("INSTANCE", std::get<1>(service_description)); EXPECT_EQ("EVENT", std::get<2>(service_description)); @@ -42,9 +39,8 @@ TEST(NameConverisonTests, get_service_description_from_name_n_type_revers) TEST(NameConverisonTests, get_service_description_from_name_n_type) { - auto service_description = rmw_iceoryx_cpp::get_service_description_from_name_n_type( - "TopicName", - "TypeName"); + auto service_description = + rmw_iceoryx_cpp::get_service_description_from_name_n_type("TopicName", "TypeName"); EXPECT_EQ("TypeName", std::get<0>(service_description)); EXPECT_EQ("TopicName", std::get<1>(service_description)); EXPECT_EQ("data", std::get<2>(service_description)); @@ -52,38 +48,32 @@ TEST(NameConverisonTests, get_service_description_from_name_n_type) TEST(NameConverisonTests, get_name_n_type_from_service_description_revers) { - auto topic_and_type = rmw_iceoryx_cpp::get_name_n_type_from_service_description( - "TypeName", - "TopicName", - "data"); + auto topic_and_type = + rmw_iceoryx_cpp::get_name_n_type_from_service_description("TypeName", "TopicName", "data"); EXPECT_EQ("TopicName", std::get<0>(topic_and_type)); EXPECT_EQ("TypeName", std::get<1>(topic_and_type)); } TEST(NameConverisonTests, get_hidden_introspection_topic) { - auto topic_and_type = rmw_iceoryx_cpp::get_name_n_type_from_service_description( - "Introspection", - "RouDI_ID", - "foo"); + auto topic_and_type = + rmw_iceoryx_cpp::get_name_n_type_from_service_description("Introspection", "RouDI_ID", "foo"); EXPECT_EQ(std::get<0>(topic_and_type), "/_iceoryx/RouDI_ID/Introspection/foo"); EXPECT_EQ(std::get<1>(topic_and_type), "iceoryx_introspection_msgs/msg/foo"); } TEST(NameConverisonTests, flip_flop) { - std::vector> topic_names_and_types = - {{"topic1", "type1"}, + std::vector> topic_names_and_types = { + {"topic1", "type1"}, {"topic2", "type2"}, {"topic3", "type3"}, {"/_iceoryx/RouDI_1/Introspection/event1", "iceoryx_introspection_msgs/msg/event1"}, {"/_iceoryx/RouDI_1/Introspection/event2", "iceoryx_introspection_msgs/msg/event2"}}; for (auto & tuple : topic_names_and_types) { - auto service_tuple = - rmw_iceoryx_cpp::get_service_description_from_name_n_type( - std::get<0>(tuple), - std::get<1>(tuple)); + auto service_tuple = rmw_iceoryx_cpp::get_service_description_from_name_n_type( + std::get<0>(tuple), std::get<1>(tuple)); auto flip_flop_tuple = rmw_iceoryx_cpp::get_name_n_type_from_service_description( std::get<0>(service_tuple), std::get<1>(service_tuple), std::get<2>(service_tuple)); EXPECT_EQ(tuple, flip_flop_tuple); @@ -92,8 +82,8 @@ TEST(NameConverisonTests, flip_flop) TEST(NameConverisonTests, flip_flop_reverse) { - std::vector> topic_names_and_types = - {{"service1", "instance1", "event1"}, + std::vector> topic_names_and_types = { + {"service1", "instance1", "event1"}, {"service2", "instance2", "event2"}, {"Introspection", "RouDI_1", "event1"}, {"type1", "topic1", "data"}}; @@ -101,10 +91,8 @@ TEST(NameConverisonTests, flip_flop_reverse) for (auto & tuple : topic_names_and_types) { auto ros_tuple = rmw_iceoryx_cpp::get_name_n_type_from_service_description( std::get<0>(tuple), std::get<1>(tuple), std::get<2>(tuple)); - auto flip_flop_tuple = - rmw_iceoryx_cpp::get_service_description_from_name_n_type( - std::get<0>(ros_tuple), - std::get<1>(ros_tuple)); + auto flip_flop_tuple = rmw_iceoryx_cpp::get_service_description_from_name_n_type( + std::get<0>(ros_tuple), std::get<1>(ros_tuple)); EXPECT_EQ(tuple, flip_flop_tuple); } } diff --git a/rmw_iceoryx_cpp/test/iceoryx_serialization_test.cpp b/rmw_iceoryx_cpp/test/iceoryx_serialization_test.cpp index c474159..778668a 100644 --- a/rmw_iceoryx_cpp/test/iceoryx_serialization_test.cpp +++ b/rmw_iceoryx_cpp/test/iceoryx_serialization_test.cpp @@ -17,7 +17,8 @@ #include -#include +#include +#include #include #include "rosidl_typesupport_cpp/message_type_support.hpp" @@ -32,7 +33,7 @@ template std::string to_string(const MessageT & msg) { - (void) msg; + (void)msg; return std::string("no to_string method defined") + typeid(MessageT).name(); } @@ -48,8 +49,7 @@ std::string to_string(const test_msgs::msg::Strings & m template void test_equality(const MessageT & expected, const MessageT & actual) { - EXPECT_EQ(expected, actual) << - "expected: " << to_string(expected) << + EXPECT_EQ(expected, actual) << "expected: " << to_string(expected) << "got: " << to_string(actual); } @@ -62,8 +62,7 @@ void test_equality(const test_msgs::msg::Strings & expected, const test_msgs::ms template< class MessageT, - class MessageFixtureF = std::function>(void)> -> + class MessageFixtureF = std::function>(void)>> void flip_flop_serialization(MessageFixtureF message_fixture) { auto ts = rosidl_typesupport_cpp::get_message_type_support_handle(); @@ -118,17 +117,13 @@ TEST(SerializationTests, cpp_flip_flop_serialize_arrays) TEST(SerializationTests, cpp_flip_flop_serialize_unbounded_sequences) { flip_flop_serialization( - std::bind( - & - get_messages_unbounded_sequences)); + std::bind(&get_messages_unbounded_sequences)); } TEST(SerializationTests, cpp_flip_flop_serialize_bounded_sequences) { flip_flop_serialization( - std::bind( - & - get_messages_bounded_sequences)); + std::bind(&get_messages_bounded_sequences)); } TEST(SerializationTests, cpp_flip_flop_serialize_multi_nested) @@ -146,18 +141,16 @@ TEST(SerializationTests, cpp_flip_flop_serialize_builtins) flip_flop_serialization(std::bind(&get_messages_builtins)); } -//TEST(SerializationTests, cpp_flip_flop_serialize_wstrings) -//{ -// flip_flop_serialization(std::bind(&get_messages_wstrings)); -//} +// TEST(SerializationTests, cpp_flip_flop_serialize_wstrings) +// { +// flip_flop_serialization(std::bind(&get_messages_wstrings)); +// } template< class MessageT, - class MessageFixtureF = std::function>(void)> -> + class MessageFixtureF = std::function>(void)>> void flip_flop_serialization( - MessageFixtureF message_fixture, - const rosidl_message_type_support_t * ts) + MessageFixtureF message_fixture, const rosidl_message_type_support_t * ts) { auto test_msgs = message_fixture(); for (auto i = 0u; i < test_msgs.size(); ++i) { @@ -216,18 +209,14 @@ TEST(SerializationTests, c_flip_flop_serialize_unbounded_sequences) { auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, UnboundedSequences); flip_flop_serialization( - std::bind( - & - get_messages_unbounded_sequences_c), ts); + std::bind(&get_messages_unbounded_sequences_c), ts); } TEST(SerializationTests, c_flip_flop_serialize_bounded_sequences) { auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BoundedSequences); flip_flop_serialization( - std::bind( - & - get_messages_bounded_sequences_c), ts); + std::bind(&get_messages_bounded_sequences_c), ts); } TEST(SerializationTests, c_flip_flop_serialize_nested) @@ -236,11 +225,12 @@ TEST(SerializationTests, c_flip_flop_serialize_nested) flip_flop_serialization(std::bind(&get_messages_nested_c), ts); } -//TEST(SerializationTests, c_flip_flop_serialize_multinested) -//{ -// auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, MultiNested); -// flip_flop_serialization(std::bind(&get_messages_multi_nested_c), ts); -//} +// TEST(SerializationTests, c_flip_flop_serialize_multinested) +// { +// auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, MultiNested); +// flip_flop_serialization( +// std::bind(&get_messages_multi_nested_c), ts); +// } TEST(SerializationTests, c_flip_flop_serialize_builtins) { diff --git a/rmw_iceoryx_cpp/test/test_msgs_c_fixtures.hpp b/rmw_iceoryx_cpp/test/test_msgs_c_fixtures.hpp index 933816b..e63bba1 100644 --- a/rmw_iceoryx_cpp/test/test_msgs_c_fixtures.hpp +++ b/rmw_iceoryx_cpp/test/test_msgs_c_fixtures.hpp @@ -12,10 +12,16 @@ // See the License for the specific language governing permissions and // limitations under the License. -#pragma once +#ifndef TEST_MSGS_C_FIXTURES_HPP_ +#define TEST_MSGS_C_FIXTURES_HPP_ + +#include +#include +#include +#include -#include "rosidl_runtime_c/string_functions.h" #include "rosidl_runtime_c/primitives_sequence_functions.h" +#include "rosidl_runtime_c/string_functions.h" #include "test_msgs/msg/arrays.h" #include "test_msgs/msg/basic_types.h" @@ -29,8 +35,7 @@ #include "test_msgs/msg/strings.h" #include "test_msgs/msg/unbounded_sequences.h" -std::vector> -get_messages_empty_c() +std::vector> get_messages_empty_c() { using T = test_msgs__msg__Empty; std::vector> vec{}; @@ -49,8 +54,8 @@ get_messages_empty_c() bool operator==(const test_msgs__msg__Empty & lhs, const test_msgs__msg__Empty & rhs) { - (void) lhs; - (void) rhs; + (void)lhs; + (void)rhs; return true; } @@ -59,8 +64,7 @@ bool operator!=(const test_msgs__msg__Empty & lhs, const test_msgs__msg__Empty & return !(lhs == rhs); } -std::vector> -get_messages_basic_types_c() +std::vector> get_messages_basic_types_c() { using T = test_msgs__msg__BasicTypes; std::vector> vec{}; @@ -166,19 +170,45 @@ get_messages_basic_types_c() bool operator==(const test_msgs__msg__BasicTypes & lhs, const test_msgs__msg__BasicTypes & rhs) { - if (lhs.bool_value != rhs.bool_value) {return false;} - if (lhs.byte_value != rhs.byte_value) {return false;} - if (lhs.char_value != rhs.char_value) {return false;} - if (lhs.float32_value != rhs.float32_value) {return false;} - if (lhs.float64_value != rhs.float64_value) {return false;} - if (lhs.int8_value != rhs.int8_value) {return false;} - if (lhs.uint8_value != rhs.uint8_value) {return false;} - if (lhs.int16_value != rhs.int16_value) {return false;} - if (lhs.uint16_value != rhs.uint16_value) {return false;} - if (lhs.int32_value != rhs.int32_value) {return false;} - if (lhs.uint32_value != rhs.uint32_value) {return false;} - if (lhs.int64_value != rhs.int64_value) {return false;} - if (lhs.uint64_value != rhs.uint64_value) {return false;} + if (lhs.bool_value != rhs.bool_value) { + return false; + } + if (lhs.byte_value != rhs.byte_value) { + return false; + } + if (lhs.char_value != rhs.char_value) { + return false; + } + if (lhs.float32_value != rhs.float32_value) { + return false; + } + if (lhs.float64_value != rhs.float64_value) { + return false; + } + if (lhs.int8_value != rhs.int8_value) { + return false; + } + if (lhs.uint8_value != rhs.uint8_value) { + return false; + } + if (lhs.int16_value != rhs.int16_value) { + return false; + } + if (lhs.uint16_value != rhs.uint16_value) { + return false; + } + if (lhs.int32_value != rhs.int32_value) { + return false; + } + if (lhs.uint32_value != rhs.uint32_value) { + return false; + } + if (lhs.int64_value != rhs.int64_value) { + return false; + } + if (lhs.uint64_value != rhs.uint64_value) { + return false; + } return true; } @@ -188,8 +218,7 @@ bool operator!=(const test_msgs__msg__BasicTypes & lhs, const test_msgs__msg__Ba return !(lhs == rhs); } -std::vector> -get_messages_constants_c() +std::vector> get_messages_constants_c() { using T = test_msgs__msg__Constants; std::vector> vec{}; @@ -209,24 +238,8 @@ get_messages_constants_c() bool operator==(const test_msgs__msg__Constants & lhs, const test_msgs__msg__Constants & rhs) { - (void) lhs; - (void) rhs; - - //TODO(karsten1987) Not sure how a equal operator should look like here - //if (lhs.BOOL_CONST, true); - //if (lhs.BYTE_CONST, 50); - //if (lhs.CHAR_CONST, 100); - //if (lhs.FLOAT32_CONST, 1.125); - //if (lhs.FLOAT64_CONST, 1.125); - //if (lhs.INT8_CONST, -50); - //if (lhs.UINT8_CONST, 200u); - //if (lhs.INT16_CONST, -1000); - //if (lhs.UINT16_CONST, 2000u); - //if (lhs.INT32_CONST, -30000); - //if (lhs.UINT32_CONST, 60000u); - //if (lhs.INT64_CONST, -40000000); - //if (lhs.UINT64_CONST, 50000000u); - + (void)lhs; + (void)rhs; return true; } @@ -235,8 +248,7 @@ bool operator!=(const test_msgs__msg__Constants & lhs, const test_msgs__msg__Con return !(lhs == rhs); } -std::vector> -get_messages_defaults_c() +std::vector> get_messages_defaults_c() { using T = test_msgs__msg__Defaults; std::vector> vec{}; @@ -256,19 +268,45 @@ get_messages_defaults_c() bool operator==(const test_msgs__msg__Defaults & lhs, const test_msgs__msg__Defaults & rhs) { - if (lhs.bool_value != rhs.bool_value) {return false;} - if (lhs.byte_value != rhs.byte_value) {return false;} - if (lhs.char_value != rhs.char_value) {return false;} - if (lhs.float32_value != rhs.float32_value) {return false;} - if (lhs.float64_value != rhs.float64_value) {return false;} - if (lhs.int8_value != rhs.int8_value) {return false;} - if (lhs.uint8_value != rhs.uint8_value) {return false;} - if (lhs.int16_value != rhs.int16_value) {return false;} - if (lhs.uint16_value != rhs.uint16_value) {return false;} - if (lhs.int32_value != rhs.int32_value) {return false;} - if (lhs.uint32_value != rhs.uint32_value) {return false;} - if (lhs.int64_value != rhs.int64_value) {return false;} - if (lhs.uint64_value != rhs.uint64_value) {return false;} + if (lhs.bool_value != rhs.bool_value) { + return false; + } + if (lhs.byte_value != rhs.byte_value) { + return false; + } + if (lhs.char_value != rhs.char_value) { + return false; + } + if (lhs.float32_value != rhs.float32_value) { + return false; + } + if (lhs.float64_value != rhs.float64_value) { + return false; + } + if (lhs.int8_value != rhs.int8_value) { + return false; + } + if (lhs.uint8_value != rhs.uint8_value) { + return false; + } + if (lhs.int16_value != rhs.int16_value) { + return false; + } + if (lhs.uint16_value != rhs.uint16_value) { + return false; + } + if (lhs.int32_value != rhs.int32_value) { + return false; + } + if (lhs.uint32_value != rhs.uint32_value) { + return false; + } + if (lhs.int64_value != rhs.int64_value) { + return false; + } + if (lhs.uint64_value != rhs.uint64_value) { + return false; + } return true; } @@ -278,8 +316,7 @@ bool operator!=(const test_msgs__msg__Defaults & lhs, const test_msgs__msg__Defa return !(lhs == rhs); } -std::vector> -get_messages_strings_c() +std::vector> get_messages_strings_c() { using T = test_msgs__msg__Strings; std::vector> vec{}; @@ -346,8 +383,12 @@ get_messages_strings_c() bool operator==(const test_msgs__msg__Strings & lhs, const test_msgs__msg__Strings & rhs) { - if (0 != strcmp(lhs.string_value.data, rhs.string_value.data)) {return false;} - if (0 != strcmp(lhs.bounded_string_value.data, rhs.bounded_string_value.data)) {return false;} + if (0 != strcmp(lhs.string_value.data, rhs.string_value.data)) { + return false; + } + if (0 != strcmp(lhs.bounded_string_value.data, rhs.bounded_string_value.data)) { + return false; + } return true; } @@ -357,8 +398,7 @@ bool operator!=(const test_msgs__msg__Strings & lhs, const test_msgs__msg__Strin return !(lhs == rhs); } -std::vector> -get_messages_arrays_c() +std::vector> get_messages_arrays_c() { using T = test_msgs__msg__Arrays; std::vector> vec{}; @@ -433,54 +473,150 @@ get_messages_arrays_c() bool operator==(const test_msgs__msg__Arrays & lhs, const test_msgs__msg__Arrays & rhs) { - if (lhs.bool_values[0] != rhs.bool_values[0]) {return false;} - if (lhs.bool_values[1] != rhs.bool_values[1]) {return false;} - if (lhs.bool_values[2] != rhs.bool_values[2]) {return false;} - if (lhs.byte_values[0] != rhs.byte_values[0]) {return false;} - if (lhs.byte_values[1] != rhs.byte_values[1]) {return false;} - if (lhs.byte_values[2] != rhs.byte_values[2]) {return false;} - if (lhs.char_values[0] != rhs.char_values[0]) {return false;} - if (lhs.char_values[1] != rhs.char_values[1]) {return false;} - if (lhs.char_values[2] != rhs.char_values[2]) {return false;} - if (lhs.float32_values[0] != rhs.float32_values[0]) {return false;} - if (lhs.float32_values[1] != rhs.float32_values[1]) {return false;} - if (lhs.float32_values[2] != rhs.float32_values[2]) {return false;} - if (lhs.float64_values[0] != rhs.float64_values[0]) {return false;} - if (lhs.float64_values[1] != rhs.float64_values[1]) {return false;} - if (lhs.float64_values[2] != rhs.float64_values[2]) {return false;} - if (lhs.int8_values[0] != rhs.int8_values[0]) {return false;} - if (lhs.int8_values[1] != rhs.int8_values[1]) {return false;} - if (lhs.int8_values[2] != rhs.int8_values[2]) {return false;} - if (lhs.uint8_values[0] != rhs.uint8_values[0]) {return false;} - if (lhs.uint8_values[1] != rhs.uint8_values[1]) {return false;} - if (lhs.uint8_values[2] != rhs.uint8_values[2]) {return false;} - if (lhs.int16_values[0] != rhs.int16_values[0]) {return false;} - if (lhs.int16_values[1] != rhs.int16_values[1]) {return false;} - if (lhs.int16_values[2] != rhs.int16_values[2]) {return false;} - if (lhs.uint16_values[0] != rhs.uint16_values[0]) {return false;} - if (lhs.uint16_values[1] != rhs.uint16_values[1]) {return false;} - if (lhs.uint16_values[2] != rhs.uint16_values[2]) {return false;} - if (lhs.int32_values[0] != rhs.int32_values[0]) {return false;} - if (lhs.int32_values[1] != rhs.int32_values[1]) {return false;} - if (lhs.int32_values[2] != rhs.int32_values[2]) {return false;} - if (lhs.uint32_values[0] != rhs.uint32_values[0]) {return false;} - if (lhs.uint32_values[1] != rhs.uint32_values[1]) {return false;} - if (lhs.uint32_values[2] != rhs.uint32_values[2]) {return false;} - if (lhs.int64_values[0] != rhs.int64_values[0]) {return false;} - if (lhs.int64_values[1] != rhs.int64_values[1]) {return false;} - if (lhs.int64_values[2] != rhs.int64_values[2]) {return false;} - if (lhs.uint64_values[0] != rhs.uint64_values[0]) {return false;} - if (lhs.uint64_values[1] != rhs.uint64_values[1]) {return false;} - if (lhs.uint64_values[2] != rhs.uint64_values[2]) {return false;} - if (lhs.basic_types_values[0] != rhs.basic_types_values[0]) {return false;} - if (lhs.basic_types_values[1] != rhs.basic_types_values[1]) {return false;} - if (lhs.basic_types_values[2] != rhs.basic_types_values[2]) {return false;} - if (lhs.constants_values[0] != rhs.constants_values[0]) {return false;} - if (lhs.constants_values[1] != rhs.constants_values[1]) {return false;} - if (lhs.constants_values[2] != rhs.constants_values[2]) {return false;} - if (lhs.defaults_values[0] != rhs.defaults_values[0]) {return false;} - if (lhs.defaults_values[1] != rhs.defaults_values[1]) {return false;} - if (lhs.defaults_values[2] != rhs.defaults_values[2]) {return false;} + if (lhs.bool_values[0] != rhs.bool_values[0]) { + return false; + } + if (lhs.bool_values[1] != rhs.bool_values[1]) { + return false; + } + if (lhs.bool_values[2] != rhs.bool_values[2]) { + return false; + } + if (lhs.byte_values[0] != rhs.byte_values[0]) { + return false; + } + if (lhs.byte_values[1] != rhs.byte_values[1]) { + return false; + } + if (lhs.byte_values[2] != rhs.byte_values[2]) { + return false; + } + if (lhs.char_values[0] != rhs.char_values[0]) { + return false; + } + if (lhs.char_values[1] != rhs.char_values[1]) { + return false; + } + if (lhs.char_values[2] != rhs.char_values[2]) { + return false; + } + if (lhs.float32_values[0] != rhs.float32_values[0]) { + return false; + } + if (lhs.float32_values[1] != rhs.float32_values[1]) { + return false; + } + if (lhs.float32_values[2] != rhs.float32_values[2]) { + return false; + } + if (lhs.float64_values[0] != rhs.float64_values[0]) { + return false; + } + if (lhs.float64_values[1] != rhs.float64_values[1]) { + return false; + } + if (lhs.float64_values[2] != rhs.float64_values[2]) { + return false; + } + if (lhs.int8_values[0] != rhs.int8_values[0]) { + return false; + } + if (lhs.int8_values[1] != rhs.int8_values[1]) { + return false; + } + if (lhs.int8_values[2] != rhs.int8_values[2]) { + return false; + } + if (lhs.uint8_values[0] != rhs.uint8_values[0]) { + return false; + } + if (lhs.uint8_values[1] != rhs.uint8_values[1]) { + return false; + } + if (lhs.uint8_values[2] != rhs.uint8_values[2]) { + return false; + } + if (lhs.int16_values[0] != rhs.int16_values[0]) { + return false; + } + if (lhs.int16_values[1] != rhs.int16_values[1]) { + return false; + } + if (lhs.int16_values[2] != rhs.int16_values[2]) { + return false; + } + if (lhs.uint16_values[0] != rhs.uint16_values[0]) { + return false; + } + if (lhs.uint16_values[1] != rhs.uint16_values[1]) { + return false; + } + if (lhs.uint16_values[2] != rhs.uint16_values[2]) { + return false; + } + if (lhs.int32_values[0] != rhs.int32_values[0]) { + return false; + } + if (lhs.int32_values[1] != rhs.int32_values[1]) { + return false; + } + if (lhs.int32_values[2] != rhs.int32_values[2]) { + return false; + } + if (lhs.uint32_values[0] != rhs.uint32_values[0]) { + return false; + } + if (lhs.uint32_values[1] != rhs.uint32_values[1]) { + return false; + } + if (lhs.uint32_values[2] != rhs.uint32_values[2]) { + return false; + } + if (lhs.int64_values[0] != rhs.int64_values[0]) { + return false; + } + if (lhs.int64_values[1] != rhs.int64_values[1]) { + return false; + } + if (lhs.int64_values[2] != rhs.int64_values[2]) { + return false; + } + if (lhs.uint64_values[0] != rhs.uint64_values[0]) { + return false; + } + if (lhs.uint64_values[1] != rhs.uint64_values[1]) { + return false; + } + if (lhs.uint64_values[2] != rhs.uint64_values[2]) { + return false; + } + if (lhs.basic_types_values[0] != rhs.basic_types_values[0]) { + return false; + } + if (lhs.basic_types_values[1] != rhs.basic_types_values[1]) { + return false; + } + if (lhs.basic_types_values[2] != rhs.basic_types_values[2]) { + return false; + } + if (lhs.constants_values[0] != rhs.constants_values[0]) { + return false; + } + if (lhs.constants_values[1] != rhs.constants_values[1]) { + return false; + } + if (lhs.constants_values[2] != rhs.constants_values[2]) { + return false; + } + if (lhs.defaults_values[0] != rhs.defaults_values[0]) { + return false; + } + if (lhs.defaults_values[1] != rhs.defaults_values[1]) { + return false; + } + if (lhs.defaults_values[2] != rhs.defaults_values[2]) { + return false; + } return true; } @@ -711,82 +847,134 @@ get_messages_unbounded_sequences_c() } bool operator==( - const test_msgs__msg__UnboundedSequences & lhs, - const test_msgs__msg__UnboundedSequences & rhs) + const test_msgs__msg__UnboundedSequences & lhs, const test_msgs__msg__UnboundedSequences & rhs) { - if (lhs.bool_values.size != rhs.bool_values.size) {return false;} - if (lhs.byte_values.size != rhs.byte_values.size) {return false;} - if (lhs.char_values.size != rhs.char_values.size) {return false;} - if (lhs.float32_values.size != rhs.float32_values.size) {return false;} - if (lhs.float64_values.size != rhs.float64_values.size) {return false;} - if (lhs.int8_values.size != rhs.int8_values.size) {return false;} - if (lhs.uint8_values.size != rhs.uint8_values.size) {return false;} - if (lhs.int16_values.size != rhs.int16_values.size) {return false;} - if (lhs.uint16_values.size != rhs.uint16_values.size) {return false;} - if (lhs.int32_values.size != rhs.int32_values.size) {return false;} - if (lhs.uint32_values.size != rhs.uint32_values.size) {return false;} - if (lhs.int64_values.size != rhs.int64_values.size) {return false;} - if (lhs.uint64_values.size != rhs.uint64_values.size) {return false;} + if (lhs.bool_values.size != rhs.bool_values.size) { + return false; + } + if (lhs.byte_values.size != rhs.byte_values.size) { + return false; + } + if (lhs.char_values.size != rhs.char_values.size) { + return false; + } + if (lhs.float32_values.size != rhs.float32_values.size) { + return false; + } + if (lhs.float64_values.size != rhs.float64_values.size) { + return false; + } + if (lhs.int8_values.size != rhs.int8_values.size) { + return false; + } + if (lhs.uint8_values.size != rhs.uint8_values.size) { + return false; + } + if (lhs.int16_values.size != rhs.int16_values.size) { + return false; + } + if (lhs.uint16_values.size != rhs.uint16_values.size) { + return false; + } + if (lhs.int32_values.size != rhs.int32_values.size) { + return false; + } + if (lhs.uint32_values.size != rhs.uint32_values.size) { + return false; + } + if (lhs.int64_values.size != rhs.int64_values.size) { + return false; + } + if (lhs.uint64_values.size != rhs.uint64_values.size) { + return false; + } if (lhs.alignment_check != rhs.alignment_check) { - fprintf(stderr, "two messages are not aligend\n"); return false; + fprintf(stderr, "two messages are not aligend\n"); + return false; } for (size_t i = 0; i < lhs.bool_values.size; ++i) { - if (lhs.bool_values.data[i] != rhs.bool_values.data[i]) {return false;} + if (lhs.bool_values.data[i] != rhs.bool_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.byte_values.size; ++i) { - if (lhs.byte_values.data[i] != rhs.byte_values.data[i]) {return false;} + if (lhs.byte_values.data[i] != rhs.byte_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.char_values.size; ++i) { - if (lhs.char_values.data[i] != rhs.char_values.data[i]) {return false;} + if (lhs.char_values.data[i] != rhs.char_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.float32_values.size; ++i) { - if (lhs.float32_values.data[i] != rhs.float32_values.data[i]) {return false;} + if (lhs.float32_values.data[i] != rhs.float32_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.float64_values.size; ++i) { - if (lhs.float64_values.data[i] != rhs.float64_values.data[i]) {return false;} + if (lhs.float64_values.data[i] != rhs.float64_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.int8_values.size; ++i) { - if (lhs.int8_values.data[i] != rhs.int8_values.data[i]) {return false;} + if (lhs.int8_values.data[i] != rhs.int8_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.uint8_values.size; ++i) { - if (lhs.uint8_values.data[i] != rhs.uint8_values.data[i]) {return false;} + if (lhs.uint8_values.data[i] != rhs.uint8_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.int16_values.size; ++i) { - if (lhs.int16_values.data[i] != rhs.int16_values.data[i]) {return false;} + if (lhs.int16_values.data[i] != rhs.int16_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.uint16_values.size; ++i) { - if (lhs.uint16_values.data[i] != rhs.uint16_values.data[i]) {return false;} + if (lhs.uint16_values.data[i] != rhs.uint16_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.int32_values.size; ++i) { - if (lhs.int32_values.data[i] != rhs.int32_values.data[i]) {return false;} + if (lhs.int32_values.data[i] != rhs.int32_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.uint32_values.size; ++i) { - if (lhs.uint32_values.data[i] != rhs.uint32_values.data[i]) {return false;} + if (lhs.uint32_values.data[i] != rhs.uint32_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.int64_values.size; ++i) { - if (lhs.int64_values.data[i] != rhs.int64_values.data[i]) {return false;} + if (lhs.int64_values.data[i] != rhs.int64_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.uint64_values.size; ++i) { - if (lhs.uint64_values.data[i] != rhs.uint64_values.data[i]) {return false;} + if (lhs.uint64_values.data[i] != rhs.uint64_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.string_values.size; ++i) { - if (0 != strcmp(lhs.string_values.data[i].data, rhs.string_values.data[i].data)) {return false;} + if (0 != strcmp(lhs.string_values.data[i].data, rhs.string_values.data[i].data)) { + return false; + } } return true; } bool operator!=( - const test_msgs__msg__UnboundedSequences & lhs, - const test_msgs__msg__UnboundedSequences & rhs) + const test_msgs__msg__UnboundedSequences & lhs, const test_msgs__msg__UnboundedSequences & rhs) { return !(lhs == rhs); } -std::vector> -get_messages_bounded_sequences_c() +std::vector> get_messages_bounded_sequences_c() { using T = test_msgs__msg__BoundedSequences; std::vector> vec{}; @@ -893,64 +1081,89 @@ get_messages_bounded_sequences_c() } bool operator==( - const test_msgs__msg__BoundedSequences & lhs, - const test_msgs__msg__BoundedSequences & rhs) + const test_msgs__msg__BoundedSequences & lhs, const test_msgs__msg__BoundedSequences & rhs) { for (size_t i = 0; i < lhs.bool_values.size; ++i) { - if (lhs.bool_values.data[i] != rhs.bool_values.data[i]) {return false;} + if (lhs.bool_values.data[i] != rhs.bool_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.byte_values.size; ++i) { - if (lhs.byte_values.data[i] != rhs.byte_values.data[i]) {return false;} + if (lhs.byte_values.data[i] != rhs.byte_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.char_values.size; ++i) { - if (lhs.char_values.data[i] != rhs.char_values.data[i]) {return false;} + if (lhs.char_values.data[i] != rhs.char_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.float32_values.size; ++i) { - if (lhs.float32_values.data[i] != rhs.float32_values.data[i]) {return false;} + if (lhs.float32_values.data[i] != rhs.float32_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.float64_values.size; ++i) { - if (lhs.float64_values.data[i] != rhs.float64_values.data[i]) {return false;} + if (lhs.float64_values.data[i] != rhs.float64_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.int8_values.size; ++i) { - if (lhs.int8_values.data[i] != rhs.int8_values.data[i]) {return false;} + if (lhs.int8_values.data[i] != rhs.int8_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.uint8_values.size; ++i) { - if (lhs.uint8_values.data[i] != rhs.uint8_values.data[i]) {return false;} + if (lhs.uint8_values.data[i] != rhs.uint8_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.int16_values.size; ++i) { - if (lhs.int16_values.data[i] != rhs.int16_values.data[i]) {return false;} + if (lhs.int16_values.data[i] != rhs.int16_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.uint16_values.size; ++i) { - if (lhs.uint16_values.data[i] != rhs.uint16_values.data[i]) {return false;} + if (lhs.uint16_values.data[i] != rhs.uint16_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.int32_values.size; ++i) { - if (lhs.int32_values.data[i] != rhs.int32_values.data[i]) {return false;} + if (lhs.int32_values.data[i] != rhs.int32_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.uint32_values.size; ++i) { - if (lhs.uint32_values.data[i] != rhs.uint32_values.data[i]) {return false;} + if (lhs.uint32_values.data[i] != rhs.uint32_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.int64_values.size; ++i) { - if (lhs.int64_values.data[i] != rhs.int64_values.data[i]) {return false;} + if (lhs.int64_values.data[i] != rhs.int64_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.uint64_values.size; ++i) { - if (lhs.uint64_values.data[i] != rhs.uint64_values.data[i]) {return false;} + if (lhs.uint64_values.data[i] != rhs.uint64_values.data[i]) { + return false; + } } for (size_t i = 0; i < lhs.string_values.size; ++i) { - if (0 != strcmp(lhs.string_values.data[i].data, rhs.string_values.data[i].data)) {return false;} + if (0 != strcmp(lhs.string_values.data[i].data, rhs.string_values.data[i].data)) { + return false; + } } return true; } bool operator!=( - const test_msgs__msg__BoundedSequences & lhs, - const test_msgs__msg__BoundedSequences & rhs) + const test_msgs__msg__BoundedSequences & lhs, const test_msgs__msg__BoundedSequences & rhs) { return !(lhs == rhs); } -std::vector> -get_messages_nested_c() +std::vector> get_messages_nested_c() { using T = test_msgs__msg__Nested; std::vector> vec{}; @@ -985,7 +1198,8 @@ bool operator!=(const test_msgs__msg__Nested & lhs, const test_msgs__msg__Nested } // TODO(karsten1987): This requires some sort of deep-copy operator for arrays and sequences, -// especially their strings as the shared ptr will cleanup the strings and eventually lead to memory leaks. +// especially their strings as the shared ptr will cleanup the strings +// and eventually lead to memory leaks. /* std::vector> get_messages_multi_nested_c() @@ -1082,8 +1296,7 @@ bool operator!=(const test_msgs__msg__MultiNested & lhs, const test_msgs__msg__M } */ -std::vector> -get_messages_builtins_c() +std::vector> get_messages_builtins_c() { using T = test_msgs__msg__Builtins; std::vector> vec{}; @@ -1107,10 +1320,18 @@ get_messages_builtins_c() bool operator==(const test_msgs__msg__Builtins & lhs, const test_msgs__msg__Builtins & rhs) { - if (lhs.duration_value.sec != rhs.duration_value.sec) {return false;} - if (lhs.duration_value.nanosec != rhs.duration_value.nanosec) {return false;} - if (lhs.time_value.sec != rhs.time_value.sec) {return false;} - if (lhs.time_value.nanosec != rhs.time_value.nanosec) {return false;} + if (lhs.duration_value.sec != rhs.duration_value.sec) { + return false; + } + if (lhs.duration_value.nanosec != rhs.duration_value.nanosec) { + return false; + } + if (lhs.time_value.sec != rhs.time_value.sec) { + return false; + } + if (lhs.time_value.nanosec != rhs.time_value.nanosec) { + return false; + } return true; } @@ -1119,3 +1340,5 @@ bool operator!=(const test_msgs__msg__Builtins & lhs, const test_msgs__msg__Buil { return !(lhs == rhs); } + +#endif // TEST_MSGS_C_FIXTURES_HPP_