diff --git a/iceoryx_ros2_bridge/src/generic_subscription.cpp b/iceoryx_ros2_bridge/src/generic_subscription.cpp index 27c2d2f..27c74ec 100644 --- a/iceoryx_ros2_bridge/src/generic_subscription.cpp +++ b/iceoryx_ros2_bridge/src/generic_subscription.cpp @@ -106,16 +106,17 @@ GenericSubscription::borrow_serialized_message(size_t capacity) rclcpp::exceptions::throw_from_rcl_error(init_return); } - auto serialized_msg = std::shared_ptr(message, - [](rmw_serialized_message_t * msg) { - auto fini_return = rmw_serialized_message_fini(msg); - delete msg; - if (fini_return != RCL_RET_OK) { - RCLCPP_ERROR_STREAM( - rclcpp::get_logger("iceoryx_ros2_bridge"), - "Failed to destroy serialized message: " << rcl_get_error_string().str); - } - }); + auto serialized_msg = std::shared_ptr( + message, + [](rmw_serialized_message_t * msg) { + auto fini_return = rmw_serialized_message_fini(msg); + delete msg; + if (fini_return != RCL_RET_OK) { + RCLCPP_ERROR_STREAM( + rclcpp::get_logger("iceoryx_ros2_bridge"), + "Failed to destroy serialized message: " << rcl_get_error_string().str); + } + }); return serialized_msg; } diff --git a/iceoryx_ros2_bridge/src/iceoryx_ros2_bridge.cpp b/iceoryx_ros2_bridge/src/iceoryx_ros2_bridge.cpp index 7bfbc08..d5f3085 100644 --- a/iceoryx_ros2_bridge/src/iceoryx_ros2_bridge.cpp +++ b/iceoryx_ros2_bridge/src/iceoryx_ros2_bridge.cpp @@ -231,7 +231,8 @@ int main(int argc, char ** argv) std::function)> cb = std::bind(&publish_to_iceoryx, std::placeholders::_1, ts, iceoryx_pubs.back()); - ros2_subs.emplace_back(std::make_shared( + ros2_subs.emplace_back( + std::make_shared( node->get_node_base_interface().get(), *ts, topic, cb)); node->get_node_topics_interface()->add_subscription(ros2_subs.back(), nullptr); } @@ -261,7 +262,8 @@ int main(int argc, char ** argv) auto ts = iceoryx_ros2_bridge::get_typesupport(type, "rosidl_typesupport_cpp"); - ros2_pubs.emplace_back(std::make_shared( + ros2_pubs.emplace_back( + std::make_shared( node->get_node_base_interface().get(), topic, *ts)); auto service_desc = diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize.cpp b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize.cpp index 5fa034f..613adfd 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize.cpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_deserialize.cpp @@ -203,8 +203,9 @@ const char * copy_payload_cpp( serialized_msg += size; } else { if (member->array_size_ > 0 && !member->is_upper_bound_) { - serialized_msg = copy_payload_fixed_array_cpp(serialized_msg, ros_message_field, - member->array_size_); + serialized_msg = copy_payload_fixed_array_cpp( + serialized_msg, ros_message_field, + member->array_size_); } else { serialized_msg = copy_payload_array_cpp(serialized_msg, ros_message_field); } @@ -271,8 +272,9 @@ const char * copy_payload_c( serialized_msg += size; } else { if (member->array_size_ > 0 && !member->is_upper_bound_) { - serialized_msg = copy_payload_fixed_array_cpp(serialized_msg, ros_message_field, - member->array_size_); + serialized_msg = copy_payload_fixed_array_cpp( + serialized_msg, ros_message_field, + member->array_size_); } else { serialized_msg = copy_payload_array_c(serialized_msg, ros_message_field); } diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_name_conversion.cpp b/rmw_iceoryx_cpp/src/internal/iceoryx_name_conversion.cpp index e1f4bd0..3cc22a0 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_name_conversion.cpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_name_conversion.cpp @@ -103,8 +103,9 @@ get_name_n_type_from_iceoryx_service_description( // ARA Naming std::string delimiter_msg = "_ara_msgs/msg/"; - return std::make_tuple("/" + instance + "/" + service + "/" + event, - service + delimiter_msg + event); + return std::make_tuple( + "/" + instance + "/" + service + "/" + event, + service + delimiter_msg + event); } } @@ -119,9 +120,10 @@ get_iceoryx_service_description( type_name = package_name + "/" + type_name; auto serviceDescriptionTuple = get_service_description_elements(topic_name, type_name); - return iox::capro::ServiceDescription(std::get<0>(serviceDescriptionTuple), - std::get<1>(serviceDescriptionTuple), - std::get<2>(serviceDescriptionTuple)); + return iox::capro::ServiceDescription( + std::get<0>(serviceDescriptionTuple), + std::get<1>(serviceDescriptionTuple), + std::get<2>(serviceDescriptionTuple)); } } // namespace rmw_iceoryx_cpp diff --git a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp index 1ab0931..fe965ab 100644 --- a/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp +++ b/rmw_iceoryx_cpp/src/internal/iceoryx_serialize.cpp @@ -242,9 +242,10 @@ void copy_data_c_ros_message( } else { void * subros_message = nullptr; size_t sub_members_size = sub_members->size_of_; - size_t array_elememts = get_array_elememts_and_assign_ros_message_field_c(member, - ros_message_field, - subros_message); + size_t array_elememts = get_array_elememts_and_assign_ros_message_field_c( + member, + ros_message_field, + subros_message); store_array_size(payloadVector, array_elememts); @@ -268,9 +269,10 @@ void copy_data_cpp_ros_message( size_t array_elements; size_t sub_members_size = sub_members->size_of_; - array_elements = get_array_elememts_and_assign_ros_message_field_cpp(member, ros_message_field, - subros_message, - sub_members_size); + array_elements = get_array_elememts_and_assign_ros_message_field_cpp( + member, ros_message_field, + subros_message, + sub_members_size); store_array_size(payloadVector, array_elements); for (size_t index = 0; index < array_elements; ++index) { serialize(subros_message, sub_members, payloadVector); 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 a1bd8b3..272921b 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 @@ -81,7 +81,8 @@ void fill_topic_containers( std::string(receiver.m_caproEventMethodID.to_cstring())); names_n_types[std::get<0>(name_and_type)] = std::get<1>(name_and_type); - subscribers_topics[std::string(receiver.m_runnable.to_cstring())].push_back(std::get<0>( + subscribers_topics[std::string(receiver.m_runnable.to_cstring())].push_back( + std::get<0>( name_and_type)); } for (auto & sender : port_sample->m_senderList) { @@ -91,7 +92,8 @@ void fill_topic_containers( std::string(sender.m_caproEventMethodID.to_cstring())); names_n_types[std::get<0>(name_and_type)] = std::get<1>(name_and_type); - publishers_topics[std::string(sender.m_runnable.to_cstring())].push_back(std::get<0>( + publishers_topics[std::string(sender.m_runnable.to_cstring())].push_back( + std::get<0>( name_and_type)); } port_receiver.releaseChunk(latest_chunk_header); @@ -186,8 +188,9 @@ rmw_ret_t fill_rmw_names_and_types( rmw_ret_t rmw_ret = RMW_RET_ERROR; 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_ret = rmw_names_and_types_init( + 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/rmw_guard_condition.cpp b/rmw_iceoryx_cpp/src/rmw_guard_condition.cpp index 4fc2a8d..a64c6dc 100644 --- a/rmw_iceoryx_cpp/src/rmw_guard_condition.cpp +++ b/rmw_iceoryx_cpp/src/rmw_guard_condition.cpp @@ -29,7 +29,8 @@ rmw_create_guard_condition(rmw_context_t * context) { RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, nullptr); - RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_create_guard_condition + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_create_guard_condition : context, context->implementation_identifier, rmw_get_implementation_identifier(), @@ -80,7 +81,8 @@ 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 + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_destroy_guard_condition : guard_condition, guard_condition->implementation_identifier, rmw_get_implementation_identifier(), diff --git a/rmw_iceoryx_cpp/src/rmw_init.cpp b/rmw_iceoryx_cpp/src/rmw_init.cpp index b526f13..9649161 100644 --- a/rmw_iceoryx_cpp/src/rmw_init.cpp +++ b/rmw_iceoryx_cpp/src/rmw_init.cpp @@ -48,7 +48,8 @@ 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 + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_init_options_copy : source options, src->implementation_identifier, rmw_get_implementation_identifier(), @@ -67,7 +68,8 @@ 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 + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_init_options_fini : options, init_options->implementation_identifier, rmw_get_implementation_identifier(), @@ -81,7 +83,8 @@ 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 + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_init : options, options->implementation_identifier, rmw_get_implementation_identifier(), @@ -110,7 +113,8 @@ 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 + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_shutdown : context, context->implementation_identifier, rmw_get_implementation_identifier(), @@ -123,7 +127,8 @@ 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 + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_context_fini : context, context->implementation_identifier, rmw_get_implementation_identifier(), diff --git a/rmw_iceoryx_cpp/src/rmw_node.cpp b/rmw_iceoryx_cpp/src/rmw_node.cpp index fead18d..e380197 100644 --- a/rmw_iceoryx_cpp/src/rmw_node.cpp +++ b/rmw_iceoryx_cpp/src/rmw_node.cpp @@ -72,7 +72,8 @@ rmw_create_node( RMW_SET_ERROR_MSG("failed to allocate memory for graph change notifier"); goto fail; } - RMW_TRY_PLACEMENT_NEW(graph_change_notifier, graph_change_notifier, goto fail, + RMW_TRY_PLACEMENT_NEW( + graph_change_notifier, graph_change_notifier, goto fail, IceoryxGraphChangeNotifier, guard_condition) // allocate iceoryx_runnable @@ -92,7 +93,8 @@ rmw_create_node( RMW_SET_ERROR_MSG("failed to allocate memory for node info"); goto fail; } - RMW_TRY_PLACEMENT_NEW(node_info, node_info, goto fail, IceoryxNodeInfo, guard_condition, + RMW_TRY_PLACEMENT_NEW( + node_info, node_info, goto fail, IceoryxNodeInfo, guard_condition, graph_change_notifier, iceoryx_runnable) node_handle->data = node_info; @@ -160,7 +162,8 @@ rmw_destroy_node(rmw_node_t * node) IceoryxNodeInfo * node_info = static_cast(node->data); if (node_info) { if (node_info->graph_change_notifier_) { - RMW_TRY_DESTRUCTOR(node_info->graph_change_notifier_->~IceoryxGraphChangeNotifier(), + RMW_TRY_DESTRUCTOR( + node_info->graph_change_notifier_->~IceoryxGraphChangeNotifier(), node_info->graph_change_notifier_, result = RMW_RET_ERROR) rmw_free(node_info->graph_change_notifier_); @@ -170,12 +173,14 @@ rmw_destroy_node(rmw_node_t * node) result = RMW_RET_ERROR; } if (node_info->iceoryx_runnable_) { - RMW_TRY_DESTRUCTOR(node_info->iceoryx_runnable_->~Runnable(), + RMW_TRY_DESTRUCTOR( + 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(), + RMW_TRY_DESTRUCTOR( + node_info->~IceoryxNodeInfo(), node_info_, result = RMW_RET_ERROR) rmw_free(node_info); diff --git a/rmw_iceoryx_cpp/src/rmw_publisher.cpp b/rmw_iceoryx_cpp/src/rmw_publisher.cpp index 8e1d355..e41d210 100644 --- a/rmw_iceoryx_cpp/src/rmw_publisher.cpp +++ b/rmw_iceoryx_cpp/src/rmw_publisher.cpp @@ -183,12 +183,14 @@ rmw_destroy_publisher(rmw_node_t * node, rmw_publisher_t * publisher) IceoryxPublisher * iceoryx_publisher = static_cast(publisher->data); if (iceoryx_publisher) { if (iceoryx_publisher->iceoryx_sender_) { - RMW_TRY_DESTRUCTOR(iceoryx_publisher->iceoryx_sender_->~Publisher(), + RMW_TRY_DESTRUCTOR( + 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(), + RMW_TRY_DESTRUCTOR( + iceoryx_publisher->~IceoryxPublisher(), iceoryx_publisher, result = RMW_RET_ERROR) rmw_free(iceoryx_publisher); diff --git a/rmw_iceoryx_cpp/src/rmw_subscription.cpp b/rmw_iceoryx_cpp/src/rmw_subscription.cpp index a1b1292..7074492 100644 --- a/rmw_iceoryx_cpp/src/rmw_subscription.cpp +++ b/rmw_iceoryx_cpp/src/rmw_subscription.cpp @@ -175,12 +175,14 @@ rmw_destroy_subscription( static_cast(subscription->data); if (iceoryx_subscription) { if (iceoryx_subscription->iceoryx_receiver_) { - RMW_TRY_DESTRUCTOR(iceoryx_subscription->iceoryx_receiver_->~Subscriber(), + RMW_TRY_DESTRUCTOR( + iceoryx_subscription->iceoryx_receiver_->~Subscriber(), iceoryx_subscription->iceoryx_receiver_, result = RMW_RET_ERROR) rmw_free(iceoryx_subscription->iceoryx_receiver_); } - RMW_TRY_DESTRUCTOR(iceoryx_subscription->~IceoryxSubscription(), + RMW_TRY_DESTRUCTOR( + iceoryx_subscription->~IceoryxSubscription(), iceoryx_subscription, result = RMW_RET_ERROR) rmw_free(iceoryx_subscription); diff --git a/rmw_iceoryx_cpp/src/rmw_take.cpp b/rmw_iceoryx_cpp/src/rmw_take.cpp index 2cb6d2f..761a66b 100644 --- a/rmw_iceoryx_cpp/src/rmw_take.cpp +++ b/rmw_iceoryx_cpp/src/rmw_take.cpp @@ -46,7 +46,8 @@ rmw_take( RCUTILS_CHECK_ARGUMENT_FOR_NULL(taken, RMW_RET_ERROR); (void)allocation; - RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_take + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_take : subscription, subscription->implementation_identifier, rmw_get_implementation_identifier(), @@ -185,7 +186,8 @@ rmw_take_loaned_message( *taken = false; - RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_take + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_take : subscription, subscription->implementation_identifier, rmw_get_implementation_identifier(), @@ -243,7 +245,8 @@ rmw_return_loaned_message_from_subscription( RCUTILS_CHECK_ARGUMENT_FOR_NULL(subscription, RMW_RET_ERROR); RCUTILS_CHECK_ARGUMENT_FOR_NULL(loaned_message, RMW_RET_ERROR); - RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_take + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_take : subscription, subscription->implementation_identifier, rmw_get_implementation_identifier(), diff --git a/rmw_iceoryx_cpp/src/rmw_trigger_guard_condition.cpp b/rmw_iceoryx_cpp/src/rmw_trigger_guard_condition.cpp index 6ac8c6b..f84e02c 100644 --- a/rmw_iceoryx_cpp/src/rmw_trigger_guard_condition.cpp +++ b/rmw_iceoryx_cpp/src/rmw_trigger_guard_condition.cpp @@ -26,7 +26,8 @@ rmw_trigger_guard_condition(const rmw_guard_condition_t * guard_condition_handle { RCUTILS_CHECK_ARGUMENT_FOR_NULL(guard_condition_handle, RMW_RET_ERROR); - RMW_CHECK_TYPE_IDENTIFIERS_MATCH(rmw_trigger_guard_condition + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + rmw_trigger_guard_condition : guard_condition_handle, guard_condition_handle->implementation_identifier, rmw_get_implementation_identifier(), diff --git a/rmw_iceoryx_cpp/src/rmw_wait.cpp b/rmw_iceoryx_cpp/src/rmw_wait.cpp index f802acd..fec9ec9 100644 --- a/rmw_iceoryx_cpp/src/rmw_wait.cpp +++ b/rmw_iceoryx_cpp/src/rmw_wait.cpp @@ -65,21 +65,29 @@ rmw_wait( static_cast(subscriptions->subscribers[i]); auto iceoryx_receiver = iceoryx_subscription->iceoryx_receiver_; - if (!iceoryx_receiver->isChunkReceiveSemaphoreSet()) { - iceoryx_receiver->setChunkReceiveSemaphore(semaphore); + // indicate that we do not have to wait if there is already a new sample + if (iceoryx_receiver->hasNewChunks()) { + goto after_wait; } + + iceoryx_receiver->setChunkReceiveSemaphore(semaphore); } // attach semaphore to all guard conditions for (size_t i = 0; i < guard_conditions->guard_condition_count; ++i) { auto iceoryx_guard_condition = static_cast(guard_conditions->guard_conditions[i]); + + // indicate that we do not have to wait if there is already a triggered guard condition + if (iceoryx_guard_condition->hasTriggered()) { + goto after_wait; + } + iceoryx_guard_condition->attachSemaphore(semaphore); } - bool semaphore_fired = false; if (!wait_timeout) { - semaphore_fired = semaphore->wait(); + semaphore->wait(); } else { struct timespec ts_start; struct timespec ts_end; @@ -92,7 +100,7 @@ rmw_wait( ts_end.tv_sec = ts_start.tv_sec + wait_timeout->sec; } ts_end.tv_nsec = nsec; - semaphore_fired = semaphore->timedWait(&ts_end, true); + semaphore->timedWait(&ts_end, true); // // for debugging // struct timespec ts_diff; @@ -108,22 +116,8 @@ rmw_wait( // printf("waited s %lu ns %lu\n", ts_diff.tv_sec, ts_diff.tv_nsec); } - if (semaphore_fired) { - // clear the semaphore again, could have received multiple triggers - // but we now evaluate each possible one - while (semaphore->tryWait()) { - } - } +after_wait: - // TODO(mphnl) Do we want to detach the samaphore from all the subscriptions and guard_conditions? - // In iceoryx we would lose the sample arrived information via the semaphore - // in the time interval between detach and re-attach - // For now detaching for guard_conditions like in the other rmw, - // but not for subscription for ensuring fastest possible processing of arrived samples. - // But it seems that the rcl layer triggers guard conditions when not in rmw_wait. - // That these were triggered is then recognized after the wait, they are not triggered - // between attaching the wait_set and the wait timeout but between detaching and re-attaching. - // This means it is not recognized by the wait_set (semaphore in our case) // reset all the subscriptions that don't have new data for (size_t i = 0; i < subscriptions->subscriber_count; ++i) { @@ -131,12 +125,15 @@ rmw_wait( static_cast(subscriptions->subscribers[i]); iox::popo::Subscriber * iceoryx_receiver = iceoryx_subscription->iceoryx_receiver_; + // remove semaphore from all receivers because next call a new waitset could be provided + iceoryx_receiver->unsetChunkReceiveSemaphore(); + if (!iceoryx_receiver->hasNewChunks()) { subscriptions->subscribers[i] = nullptr; } } - // reset all the guard_conditions that havenot triggered + // reset all the guard_conditions that have not triggered for (size_t i = 0; i < guard_conditions->guard_condition_count; ++i) { auto iceoryx_guard_condition = static_cast(guard_conditions->guard_conditions[i]); @@ -150,6 +147,11 @@ rmw_wait( } } + // clear the semaphore + // events that triggered it and where not yet collected will be seen on next rmw_wait + while (semaphore->tryWait()) { + } + return RMW_RET_OK; } } // extern "C" diff --git a/rmw_iceoryx_cpp/src/rmw_wait_set.cpp b/rmw_iceoryx_cpp/src/rmw_wait_set.cpp index 27eab15..07067d5 100644 --- a/rmw_iceoryx_cpp/src/rmw_wait_set.cpp +++ b/rmw_iceoryx_cpp/src/rmw_wait_set.cpp @@ -56,7 +56,8 @@ rmw_create_wait_set(rmw_context_t * context, size_t max_conditions) RMW_SET_ERROR_MSG("failed to allocate memory for wait_set data"); goto fail; } - RMW_TRY_PLACEMENT_NEW(process_receiver, + RMW_TRY_PLACEMENT_NEW( + process_receiver, process_receiver, goto fail, iox::popo::Subscriber, @@ -82,7 +83,8 @@ 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(), + RMW_TRY_DESTRUCTOR_FROM_WITHIN_FAILURE( + process_receiver->~Subscriber(), iox::popo::Subscriber) rmw_free(process_receiver); } @@ -113,7 +115,8 @@ rmw_destroy_wait_set(rmw_wait_set_t * wait_set) auto iceoryx_wait_set = static_cast(wait_set->data); if (iceoryx_wait_set) { if (iceoryx_wait_set->iceoryx_receiver_) { - RMW_TRY_DESTRUCTOR(iceoryx_wait_set->iceoryx_receiver_->~Subscriber(), + RMW_TRY_DESTRUCTOR( + 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_node.hpp b/rmw_iceoryx_cpp/src/types/iceoryx_node.hpp index ea1e75d..2fd5fa3 100644 --- a/rmw_iceoryx_cpp/src/types/iceoryx_node.hpp +++ b/rmw_iceoryx_cpp/src/types/iceoryx_node.hpp @@ -44,7 +44,8 @@ class IceoryxGraphChangeNotifier iceoryx_guard_condition_ = nullptr; } else { iceoryx_guard_condition_ = static_cast(guard_condition->data); - RMW_CHECK_TYPE_IDENTIFIERS_MATCH(IceoryxGraphChangeNotifier + RMW_CHECK_TYPE_IDENTIFIERS_MATCH( + IceoryxGraphChangeNotifier : guard_condition, guard_condition->implementation_identifier, rmw_get_implementation_identifier(),