diff --git a/rmw_zenoh_cpp/CMakeLists.txt b/rmw_zenoh_cpp/CMakeLists.txt index 89b5a598..2163afae 100644 --- a/rmw_zenoh_cpp/CMakeLists.txt +++ b/rmw_zenoh_cpp/CMakeLists.txt @@ -21,6 +21,7 @@ find_package(rcutils REQUIRED) find_package(rosidl_typesupport_fastrtps_c REQUIRED) find_package(rosidl_typesupport_fastrtps_cpp REQUIRED) find_package(rmw REQUIRED) +find_package(tracetools REQUIRED) find_package(zenoh_c_vendor REQUIRED) add_library(rmw_zenoh_cpp SHARED @@ -68,6 +69,7 @@ target_link_libraries(rmw_zenoh_cpp rosidl_typesupport_fastrtps_c::rosidl_typesupport_fastrtps_c rosidl_typesupport_fastrtps_cpp::rosidl_typesupport_fastrtps_cpp rmw::rmw + tracetools::tracetools zenohc::lib ) diff --git a/rmw_zenoh_cpp/package.xml b/rmw_zenoh_cpp/package.xml index e1d2a24a..97695c92 100644 --- a/rmw_zenoh_cpp/package.xml +++ b/rmw_zenoh_cpp/package.xml @@ -25,6 +25,7 @@ rosidl_typesupport_fastrtps_c rosidl_typesupport_fastrtps_cpp rmw + tracetools ament_lint_auto ament_lint_common diff --git a/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp index 1236d453..9d21c0dd 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_client_data.cpp @@ -40,6 +40,8 @@ #include "rmw/get_topic_endpoint_info.h" #include "rmw/impl/cpp/macros.hpp" +#include "tracetools/tracetools.h" + namespace { ///============================================================================= @@ -451,6 +453,12 @@ rmw_ret_t ClientData::send_request( size_t data_length = ser.get_serialized_data_length(); *sequence_id = sequence_number_++; + TRACETOOLS_TRACEPOINT( + rmw_send_request, + static_cast(rmw_client_), + static_cast(ros_request), + *sequence_id); + // Send request z_get_options_t opts; z_get_options_default(&opts); diff --git a/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp index c61daa2a..41b782a5 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_node_data.cpp @@ -144,6 +144,7 @@ bool NodeData::create_pub_data( auto pub_data = PublisherData::make( std::move(session), + publisher, node_, entity_->node_info(), id_, @@ -279,6 +280,7 @@ bool NodeData::create_service_data( auto service_data = ServiceData::make( std::move(session), node_, + service, entity_->node_info(), id_, std::move(id), diff --git a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp index f54c50ab..66deeef1 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.cpp @@ -35,6 +35,8 @@ #include "rmw/get_topic_endpoint_info.h" #include "rmw/impl/cpp/macros.hpp" +#include "tracetools/tracetools.h" + namespace rmw_zenoh_cpp { // TODO(yuyuan): SHM, make this configurable @@ -43,6 +45,7 @@ namespace rmw_zenoh_cpp ///============================================================================= std::shared_ptr PublisherData::make( std::shared_ptr session, + const rmw_publisher_t * const rmw_publisher, const rmw_node_t * const node, liveliness::NodeInfo node_info, std::size_t node_id, @@ -192,6 +195,7 @@ std::shared_ptr PublisherData::make( return std::shared_ptr( new PublisherData{ + rmw_publisher, node, std::move(entity), std::move(session), @@ -205,6 +209,7 @@ std::shared_ptr PublisherData::make( ///============================================================================= PublisherData::PublisherData( + const rmw_publisher_t * const rmw_publisher, const rmw_node_t * rmw_node, std::shared_ptr entity, std::shared_ptr sess, @@ -213,7 +218,8 @@ PublisherData::PublisherData( z_owned_liveliness_token_t token, const void * type_support_impl, std::unique_ptr type_support) -: rmw_node_(rmw_node), +: rmw_publisher_(rmw_publisher), + rmw_node_(rmw_node), entity_(std::move(entity)), sess_(std::move(sess)), pub_(std::move(pub)), @@ -311,9 +317,12 @@ rmw_ret_t PublisherData::publish( z_owned_bytes_t attachment; uint8_t local_gid[RMW_GID_STORAGE_SIZE]; entity_->copy_gid(local_gid); - create_map_and_set_sequence_num(&attachment, sequence_number_++, local_gid); + int64_t source_timestamp = 0; + create_map_and_set_sequence_num(&attachment, sequence_number_++, local_gid, &source_timestamp); options.attachment = z_move(attachment); + TRACETOOLS_TRACEPOINT( + rmw_publish, static_cast(rmw_publisher_), ros_message, source_timestamp); z_owned_bytes_t payload; if (shmbuf.has_value()) { z_bytes_from_shm_mut(&payload, z_move(shmbuf.value())); @@ -360,11 +369,14 @@ rmw_ret_t PublisherData::publish_serialized_message( uint8_t local_gid[RMW_GID_STORAGE_SIZE]; entity_->copy_gid(local_gid); z_owned_bytes_t attachment; - create_map_and_set_sequence_num(&attachment, sequence_number_++, local_gid); + int64_t source_timestamp = 0; + create_map_and_set_sequence_num(&attachment, sequence_number_++, local_gid, &source_timestamp); options.attachment = z_move(attachment); z_owned_bytes_t payload; z_bytes_copy_from_buf(&payload, serialized_message->buffer, data_length); + TRACETOOLS_TRACEPOINT( + rmw_publish, static_cast(rmw_publisher_), serialized_message, source_timestamp); z_result_t res = z_publisher_put(z_loan(pub_), z_move(payload), &options); if (res != Z_OK) { if (res == Z_ESESSION_CLOSED) { diff --git a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.hpp b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.hpp index 1853ff8a..f38bb4c8 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_publisher_data.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_publisher_data.hpp @@ -44,6 +44,7 @@ class PublisherData final // Make a shared_ptr of PublisherData. static std::shared_ptr make( std::shared_ptr session, + const rmw_publisher_t * const rmw_publisher, const rmw_node_t * const node, liveliness::NodeInfo node_info, std::size_t node_id, @@ -89,6 +90,7 @@ class PublisherData final private: // Constructor. PublisherData( + const rmw_publisher_t * const rmw_publisher, const rmw_node_t * rmw_node, std::shared_ptr entity, std::shared_ptr sess, @@ -100,6 +102,8 @@ class PublisherData final // Internal mutex. mutable std::mutex mutex_; + // The rmw publisher + const rmw_publisher_t * rmw_publisher_; // The parent node. const rmw_node_t * rmw_node_; // The Entity generated for the publisher. diff --git a/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp b/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp index 3d456a02..aebfe632 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_service_data.cpp @@ -36,6 +36,8 @@ #include "rmw/get_topic_endpoint_info.h" #include "rmw/impl/cpp/macros.hpp" +#include "tracetools/tracetools.h" + namespace rmw_zenoh_cpp { ///============================================================================== @@ -67,6 +69,7 @@ void service_data_handler(z_loaned_query_t * query, void * data) std::shared_ptr ServiceData::make( std::shared_ptr session, const rmw_node_t * const node, + const rmw_service_t * rmw_service, liveliness::NodeInfo node_info, std::size_t node_id, std::size_t service_id, @@ -149,6 +152,7 @@ std::shared_ptr ServiceData::make( auto service_data = std::shared_ptr( new ServiceData{ node, + rmw_service, std::move(entity), session, request_members, @@ -228,6 +232,7 @@ std::shared_ptr ServiceData::make( ///============================================================================= ServiceData::ServiceData( const rmw_node_t * rmw_node, + const rmw_service_t * rmw_service, std::shared_ptr entity, std::shared_ptr sess, const void * request_type_support_impl, @@ -235,6 +240,7 @@ ServiceData::ServiceData( std::unique_ptr request_type_support, std::unique_ptr response_type_support) : rmw_node_(rmw_node), + rmw_service_(rmw_service), entity_(std::move(entity)), sess_(std::move(sess)), request_type_support_impl_(request_type_support_impl), @@ -455,11 +461,20 @@ rmw_ret_t ServiceData::send_response( z_query_reply_options_default(&options); z_owned_bytes_t attachment; + int64_t source_timestamp = 0; rmw_zenoh_cpp::create_map_and_set_sequence_num( &attachment, request_id->sequence_number, - request_id->writer_guid); + request_id->writer_guid, &source_timestamp); options.attachment = z_move(attachment); + TRACETOOLS_TRACEPOINT( + rmw_send_response, + static_cast(rmw_service_), + static_cast(ros_response), + request_id->writer_guid, + request_id->sequence_number, + source_timestamp); + z_owned_bytes_t payload; z_bytes_copy_from_buf( &payload, reinterpret_cast(response_bytes), data_length); diff --git a/rmw_zenoh_cpp/src/detail/rmw_service_data.hpp b/rmw_zenoh_cpp/src/detail/rmw_service_data.hpp index a8bcbd66..15107653 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_service_data.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_service_data.hpp @@ -49,6 +49,7 @@ class ServiceData final static std::shared_ptr make( std::shared_ptr session, const rmw_node_t * const node, + const rmw_service_t * rmw_service, liveliness::NodeInfo node_info, std::size_t node_id, std::size_t service_id, @@ -98,6 +99,7 @@ class ServiceData final // Constructor. ServiceData( const rmw_node_t * rmw_node, + const rmw_service_t * rmw_service, std::shared_ptr entity, std::shared_ptr sess, const void * request_type_support_impl, @@ -109,6 +111,7 @@ class ServiceData final mutable std::mutex mutex_; // The parent node. const rmw_node_t * rmw_node_; + const rmw_service_t * rmw_service_; // The Entity generated for the service. std::shared_ptr entity_; // An owned keyexpression. diff --git a/rmw_zenoh_cpp/src/detail/zenoh_utils.cpp b/rmw_zenoh_cpp/src/detail/zenoh_utils.cpp index be5721b7..d5a5ecd1 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_utils.cpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_utils.cpp @@ -40,13 +40,19 @@ ZenohSession::~ZenohSession() ///============================================================================= void create_map_and_set_sequence_num( - z_owned_bytes_t * out_bytes, int64_t sequence_number, uint8_t gid[RMW_GID_STORAGE_SIZE]) + z_owned_bytes_t * out_bytes, + int64_t sequence_number, + uint8_t gid[RMW_GID_STORAGE_SIZE], + int64_t * source_timestamp) { auto now = std::chrono::system_clock::now().time_since_epoch(); auto now_ns = std::chrono::duration_cast(now); - int64_t source_timestamp = now_ns.count(); + int64_t timestamp = now_ns.count(); + if (nullptr != source_timestamp) { + *source_timestamp = timestamp; + } - AttachmentData data(sequence_number, source_timestamp, gid); + AttachmentData data(sequence_number, timestamp, gid); data.serialize_to_zbytes(out_bytes); } diff --git a/rmw_zenoh_cpp/src/detail/zenoh_utils.hpp b/rmw_zenoh_cpp/src/detail/zenoh_utils.hpp index ae2aed3a..7080771b 100644 --- a/rmw_zenoh_cpp/src/detail/zenoh_utils.hpp +++ b/rmw_zenoh_cpp/src/detail/zenoh_utils.hpp @@ -44,7 +44,8 @@ class ZenohSession final void create_map_and_set_sequence_num( z_owned_bytes_t * out_bytes, int64_t sequence_number, - uint8_t gid[RMW_GID_STORAGE_SIZE]); + uint8_t gid[RMW_GID_STORAGE_SIZE], + int64_t * source_timestamp = nullptr); ///============================================================================= // A class to store the replies to service requests. diff --git a/rmw_zenoh_cpp/src/rmw_zenoh.cpp b/rmw_zenoh_cpp/src/rmw_zenoh.cpp index 1e13a710..f2e58cfa 100644 --- a/rmw_zenoh_cpp/src/rmw_zenoh.cpp +++ b/rmw_zenoh_cpp/src/rmw_zenoh.cpp @@ -56,6 +56,8 @@ #include "rmw/validate_namespace.h" #include "rmw/validate_node_name.h" +#include "tracetools/tracetools.h" + namespace { //============================================================================== @@ -454,6 +456,14 @@ rmw_create_publisher( free_topic_name.cancel(); free_rmw_publisher.cancel(); + if (TRACETOOLS_TRACEPOINT_ENABLED(rmw_publisher_init)) { + rmw_gid_t gid{}; + // Trigger tracepoint even if we cannot get the GID + rmw_ret_t gid_ret = rmw_get_gid_for_publisher(rmw_publisher, &gid); + static_cast(gid_ret); + TRACETOOLS_DO_TRACEPOINT( + rmw_publisher_init, static_cast(rmw_publisher), gid.data); + } return rmw_publisher; } @@ -990,6 +1000,11 @@ rmw_create_subscription( free_topic_name.cancel(); free_rmw_subscription.cancel(); + // rmw does not require GIDs for subscriptions, and GIDs in rmw_zenoh are not based on any ID of + // the underlying zenoh objects, so there is no need to collect a GID here + rmw_gid_t gid{}; + TRACETOOLS_TRACEPOINT( + rmw_subscription_init, static_cast(rmw_subscription), gid.data); return rmw_subscription; } @@ -1134,7 +1149,18 @@ rmw_take( static_cast(subscription->data); RMW_CHECK_ARGUMENT_FOR_NULL(sub_data, RMW_RET_INVALID_ARGUMENT); - return sub_data->take_one_message(ros_message, nullptr, taken); + if (!TRACETOOLS_TRACEPOINT_ENABLED(rmw_take)) { + return sub_data->take_one_message(ros_message, nullptr, taken); + } + rmw_message_info_t message_info{}; + rmw_ret_t ret = sub_data->take_one_message(ros_message, &message_info, taken); + TRACETOOLS_DO_TRACEPOINT( + rmw_take, + static_cast(subscription), + static_cast(ros_message), + message_info.source_timestamp, + *taken); + return ret; } //============================================================================== @@ -1163,7 +1189,14 @@ rmw_take_with_info( static_cast(subscription->data); RMW_CHECK_ARGUMENT_FOR_NULL(sub_data, RMW_RET_INVALID_ARGUMENT); - return sub_data->take_one_message(ros_message, message_info, taken); + rmw_ret_t ret = sub_data->take_one_message(ros_message, message_info, taken); + TRACETOOLS_TRACEPOINT( + rmw_take, + static_cast(subscription), + static_cast(ros_message), + message_info->source_timestamp, + *taken); + return ret; } //============================================================================== @@ -1269,11 +1302,18 @@ __rmw_take_serialized( static_cast(subscription->data); RMW_CHECK_ARGUMENT_FOR_NULL(sub_data, RMW_RET_INVALID_ARGUMENT); - return sub_data->take_serialized_message( + rmw_ret_t ret = sub_data->take_serialized_message( serialized_message, taken, message_info ); + TRACETOOLS_TRACEPOINT( + rmw_take, + static_cast(subscription), + static_cast(serialized_message), + message_info->source_timestamp, + *taken); + return ret; } } // namespace @@ -1467,6 +1507,12 @@ rmw_create_client( free_rmw_client.cancel(); free_service_name.cancel(); + if (TRACETOOLS_TRACEPOINT_ENABLED(rmw_client_init)) { + auto client_data = static_cast(rmw_client->data); + rmw_gid_t gid{}; + client_data->copy_gid(gid.data); + TRACETOOLS_DO_TRACEPOINT(rmw_client_init, static_cast(rmw_client), gid.data); + } return rmw_client; } @@ -1561,7 +1607,15 @@ rmw_take_response( client->data, "Unable to retrieve client_data from client.", RMW_RET_INVALID_ARGUMENT); RMW_CHECK_ARGUMENT_FOR_NULL(ros_response, RMW_RET_INVALID_ARGUMENT); - return client_data->take_response(request_header, ros_response, taken); + rmw_ret_t ret = client_data->take_response(request_header, ros_response, taken); + TRACETOOLS_TRACEPOINT( + rmw_take_response, + static_cast(client), + static_cast(ros_response), + (nullptr != request_header ? request_header->request_id.sequence_number : 0LL), + (nullptr != request_header ? request_header->source_timestamp : 0LL), + *taken); + return ret; } //============================================================================== @@ -1779,10 +1833,18 @@ rmw_take_request( RMW_CHECK_ARGUMENT_FOR_NULL(request_header, RMW_RET_INVALID_ARGUMENT); RMW_CHECK_ARGUMENT_FOR_NULL(ros_request, RMW_RET_INVALID_ARGUMENT); - return service_data->take_request( + rmw_ret_t ret = service_data->take_request( request_header, ros_request, taken); + TRACETOOLS_TRACEPOINT( + rmw_take_request, + static_cast(service), + static_cast(ros_request), + request_header->request_id.writer_guid, + request_header->request_id.sequence_number, + *taken); + return ret; } //==============================================================================