@@ -492,7 +492,7 @@ class AnySubscriptionCallback
492492 std::shared_ptr<ROSMessageType> message,
493493 const rclcpp::MessageInfo & message_info)
494494 {
495- TRACEPOINT (callback_start, static_cast <const void *>(this ), false );
495+ TRACETOOLS_TRACEPOINT (callback_start, static_cast <const void *>(this ), false );
496496 // Check if the variant is "unset", throw if it is.
497497 if (callback_variant_.index () == 0 ) {
498498 if (std::get<0 >(callback_variant_) == nullptr ) {
@@ -583,7 +583,7 @@ class AnySubscriptionCallback
583583 static_assert (always_false_v<T>, " unhandled callback type" );
584584 }
585585 }, callback_variant_);
586- TRACEPOINT (callback_end, static_cast <const void *>(this ));
586+ TRACETOOLS_TRACEPOINT (callback_end, static_cast <const void *>(this ));
587587 }
588588
589589 // Dispatch when input is a serialized message and the output could be anything.
@@ -592,7 +592,7 @@ class AnySubscriptionCallback
592592 std::shared_ptr<rclcpp::SerializedMessage> serialized_message,
593593 const rclcpp::MessageInfo & message_info)
594594 {
595- TRACEPOINT (callback_start, static_cast <const void *>(this ), false );
595+ TRACETOOLS_TRACEPOINT (callback_start, static_cast <const void *>(this ), false );
596596 // Check if the variant is "unset", throw if it is.
597597 if (callback_variant_.index () == 0 ) {
598598 if (std::get<0 >(callback_variant_) == nullptr ) {
@@ -663,15 +663,15 @@ class AnySubscriptionCallback
663663 static_assert (always_false_v<T>, " unhandled callback type" );
664664 }
665665 }, callback_variant_);
666- TRACEPOINT (callback_end, static_cast <const void *>(this ));
666+ TRACETOOLS_TRACEPOINT (callback_end, static_cast <const void *>(this ));
667667 }
668668
669669 void
670670 dispatch_intra_process (
671671 std::shared_ptr<const SubscribedType> message,
672672 const rclcpp::MessageInfo & message_info)
673673 {
674- TRACEPOINT (callback_start, static_cast <const void *>(this ), true );
674+ TRACETOOLS_TRACEPOINT (callback_start, static_cast <const void *>(this ), true );
675675 // Check if the variant is "unset", throw if it is.
676676 if (callback_variant_.index () == 0 ) {
677677 if (std::get<0 >(callback_variant_) == nullptr ) {
@@ -793,15 +793,15 @@ class AnySubscriptionCallback
793793 static_assert (always_false_v<T>, " unhandled callback type" );
794794 }
795795 }, callback_variant_);
796- TRACEPOINT (callback_end, static_cast <const void *>(this ));
796+ TRACETOOLS_TRACEPOINT (callback_end, static_cast <const void *>(this ));
797797 }
798798
799799 void
800800 dispatch_intra_process (
801801 std::unique_ptr<SubscribedType, SubscribedTypeDeleter> message,
802802 const rclcpp::MessageInfo & message_info)
803803 {
804- TRACEPOINT (callback_start, static_cast <const void *>(this ), true );
804+ TRACETOOLS_TRACEPOINT (callback_start, static_cast <const void *>(this ), true );
805805 // Check if the variant is "unset", throw if it is.
806806 if (callback_variant_.index () == 0 ) {
807807 if (std::get<0 >(callback_variant_) == nullptr ) {
@@ -927,7 +927,7 @@ class AnySubscriptionCallback
927927 static_assert (always_false_v<T>, " unhandled callback type" );
928928 }
929929 }, callback_variant_);
930- TRACEPOINT (callback_end, static_cast <const void *>(this ));
930+ TRACETOOLS_TRACEPOINT (callback_end, static_cast <const void *>(this ));
931931 }
932932
933933 constexpr
@@ -965,9 +965,9 @@ class AnySubscriptionCallback
965965#ifndef TRACETOOLS_DISABLED
966966 std::visit (
967967 [this ](auto && callback) {
968- if (TRACEPOINT_ENABLED (rclcpp_callback_register)) {
968+ if (TRACETOOLS_TRACEPOINT_ENABLED (rclcpp_callback_register)) {
969969 char * symbol = tracetools::get_symbol (callback);
970- DO_TRACEPOINT (
970+ TRACETOOLS_DO_TRACEPOINT (
971971 rclcpp_callback_register,
972972 static_cast <const void *>(this ),
973973 symbol);
0 commit comments