diff --git a/rclcpp/include/rclcpp/any_service_callback.hpp b/rclcpp/include/rclcpp/any_service_callback.hpp index f8c2592fc5..918d8e5a29 100644 --- a/rclcpp/include/rclcpp/any_service_callback.hpp +++ b/rclcpp/include/rclcpp/any_service_callback.hpp @@ -156,7 +156,7 @@ class AnyServiceCallback const std::shared_ptr & request_header, std::shared_ptr request) { - TRACEPOINT(callback_start, static_cast(this), false); + TRACETOOLS_TRACEPOINT(callback_start, static_cast(this), false); if (std::holds_alternative(callback_)) { // TODO(ivanpauno): Remove the set method, and force the users of this class // to pass a callback at construnciton. @@ -182,7 +182,7 @@ class AnyServiceCallback const auto & cb = std::get(callback_); cb(request_header, std::move(request), response); } - TRACEPOINT(callback_end, static_cast(this)); + TRACETOOLS_TRACEPOINT(callback_end, static_cast(this)); return response; } @@ -191,9 +191,9 @@ class AnyServiceCallback #ifndef TRACETOOLS_DISABLED std::visit( [this](auto && arg) { - if (TRACEPOINT_ENABLED(rclcpp_callback_register)) { + if (TRACETOOLS_TRACEPOINT_ENABLED(rclcpp_callback_register)) { char * symbol = tracetools::get_symbol(arg); - DO_TRACEPOINT( + TRACETOOLS_DO_TRACEPOINT( rclcpp_callback_register, static_cast(this), symbol); diff --git a/rclcpp/include/rclcpp/any_subscription_callback.hpp b/rclcpp/include/rclcpp/any_subscription_callback.hpp index 65b29d8535..116eae44db 100644 --- a/rclcpp/include/rclcpp/any_subscription_callback.hpp +++ b/rclcpp/include/rclcpp/any_subscription_callback.hpp @@ -492,7 +492,7 @@ class AnySubscriptionCallback std::shared_ptr message, const rclcpp::MessageInfo & message_info) { - TRACEPOINT(callback_start, static_cast(this), false); + TRACETOOLS_TRACEPOINT(callback_start, static_cast(this), false); // Check if the variant is "unset", throw if it is. if (callback_variant_.index() == 0) { if (std::get<0>(callback_variant_) == nullptr) { @@ -583,7 +583,7 @@ class AnySubscriptionCallback static_assert(always_false_v, "unhandled callback type"); } }, callback_variant_); - TRACEPOINT(callback_end, static_cast(this)); + TRACETOOLS_TRACEPOINT(callback_end, static_cast(this)); } // Dispatch when input is a serialized message and the output could be anything. @@ -592,7 +592,7 @@ class AnySubscriptionCallback std::shared_ptr serialized_message, const rclcpp::MessageInfo & message_info) { - TRACEPOINT(callback_start, static_cast(this), false); + TRACETOOLS_TRACEPOINT(callback_start, static_cast(this), false); // Check if the variant is "unset", throw if it is. if (callback_variant_.index() == 0) { if (std::get<0>(callback_variant_) == nullptr) { @@ -663,7 +663,7 @@ class AnySubscriptionCallback static_assert(always_false_v, "unhandled callback type"); } }, callback_variant_); - TRACEPOINT(callback_end, static_cast(this)); + TRACETOOLS_TRACEPOINT(callback_end, static_cast(this)); } void @@ -671,7 +671,7 @@ class AnySubscriptionCallback std::shared_ptr message, const rclcpp::MessageInfo & message_info) { - TRACEPOINT(callback_start, static_cast(this), true); + TRACETOOLS_TRACEPOINT(callback_start, static_cast(this), true); // Check if the variant is "unset", throw if it is. if (callback_variant_.index() == 0) { if (std::get<0>(callback_variant_) == nullptr) { @@ -793,7 +793,7 @@ class AnySubscriptionCallback static_assert(always_false_v, "unhandled callback type"); } }, callback_variant_); - TRACEPOINT(callback_end, static_cast(this)); + TRACETOOLS_TRACEPOINT(callback_end, static_cast(this)); } void @@ -801,7 +801,7 @@ class AnySubscriptionCallback std::unique_ptr message, const rclcpp::MessageInfo & message_info) { - TRACEPOINT(callback_start, static_cast(this), true); + TRACETOOLS_TRACEPOINT(callback_start, static_cast(this), true); // Check if the variant is "unset", throw if it is. if (callback_variant_.index() == 0) { if (std::get<0>(callback_variant_) == nullptr) { @@ -927,7 +927,7 @@ class AnySubscriptionCallback static_assert(always_false_v, "unhandled callback type"); } }, callback_variant_); - TRACEPOINT(callback_end, static_cast(this)); + TRACETOOLS_TRACEPOINT(callback_end, static_cast(this)); } constexpr @@ -965,9 +965,9 @@ class AnySubscriptionCallback #ifndef TRACETOOLS_DISABLED std::visit( [this](auto && callback) { - if (TRACEPOINT_ENABLED(rclcpp_callback_register)) { + if (TRACETOOLS_TRACEPOINT_ENABLED(rclcpp_callback_register)) { char * symbol = tracetools::get_symbol(callback); - DO_TRACEPOINT( + TRACETOOLS_DO_TRACEPOINT( rclcpp_callback_register, static_cast(this), symbol); diff --git a/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp b/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp index 91ea91a7c3..cc576bab71 100644 --- a/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp +++ b/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp @@ -87,7 +87,7 @@ class SubscriptionIntraProcess buffer_type), any_callback_(callback) { - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_subscription_callback_added, static_cast(this), static_cast(&any_callback_)); diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index f4627cc96c..88efc68205 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -421,7 +421,7 @@ class Publisher : public PublisherBase void do_inter_process_publish(const ROSMessageType & msg) { - TRACEPOINT(rclcpp_publish, nullptr, static_cast(&msg)); + TRACETOOLS_TRACEPOINT(rclcpp_publish, nullptr, static_cast(&msg)); auto status = rcl_publish(publisher_handle_.get(), &msg, nullptr); if (RCL_RET_PUBLISHER_INVALID == status) { diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index 3cfc11e9ca..23caf5dc96 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -348,7 +348,7 @@ class Service rclcpp::exceptions::throw_from_rcl_error(ret, "could not create service"); } - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_service_callback_added, static_cast(get_service_handle().get()), static_cast(&any_callback_)); @@ -383,7 +383,7 @@ class Service } service_handle_ = service_handle; - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_service_callback_added, static_cast(get_service_handle().get()), static_cast(&any_callback_)); @@ -420,7 +420,7 @@ class Service // In this case, rcl owns the service handle memory service_handle_ = std::shared_ptr(new rcl_service_t); service_handle_->impl = service_handle->impl; - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_service_callback_added, static_cast(get_service_handle().get()), static_cast(&any_callback_)); diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index d9e84b29f8..e44c26a780 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -185,7 +185,7 @@ class Subscription : public SubscriptionBase this->get_topic_name(), // important to get like this, as it has the fully-qualified name qos_profile, resolve_intra_process_buffer_type(options_.intra_process_buffer_type, callback)); - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_subscription_init, static_cast(get_subscription_handle().get()), static_cast(subscription_intra_process_.get())); @@ -201,11 +201,11 @@ class Subscription : public SubscriptionBase this->subscription_topic_statistics_ = std::move(subscription_topic_statistics); } - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_subscription_init, static_cast(get_subscription_handle().get()), static_cast(this)); - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_subscription_callback_added, static_cast(this), static_cast(&any_callback_)); diff --git a/rclcpp/include/rclcpp/timer.hpp b/rclcpp/include/rclcpp/timer.hpp index 91b1705985..cc40736ee9 100644 --- a/rclcpp/include/rclcpp/timer.hpp +++ b/rclcpp/include/rclcpp/timer.hpp @@ -223,14 +223,14 @@ class GenericTimer : public TimerBase ) : TimerBase(clock, period, context), callback_(std::forward(callback)) { - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_timer_callback_added, static_cast(get_timer_handle().get()), reinterpret_cast(&callback_)); #ifndef TRACETOOLS_DISABLED - if (TRACEPOINT_ENABLED(rclcpp_callback_register)) { + if (TRACETOOLS_TRACEPOINT_ENABLED(rclcpp_callback_register)) { char * symbol = tracetools::get_symbol(callback_); - DO_TRACEPOINT( + TRACETOOLS_DO_TRACEPOINT( rclcpp_callback_register, reinterpret_cast(&callback_), symbol); @@ -269,9 +269,9 @@ class GenericTimer : public TimerBase void execute_callback() override { - TRACEPOINT(callback_start, reinterpret_cast(&callback_), false); + TRACETOOLS_TRACEPOINT(callback_start, reinterpret_cast(&callback_), false); execute_callback_delegate<>(); - TRACEPOINT(callback_end, reinterpret_cast(&callback_)); + TRACETOOLS_TRACEPOINT(callback_end, reinterpret_cast(&callback_)); } // void specialization diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index 9bafbe3106..806c94d32b 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -525,13 +525,13 @@ Executor::execute_any_executable(AnyExecutable & any_exec) return; } if (any_exec.timer) { - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_executor_execute, static_cast(any_exec.timer->get_timer_handle().get())); execute_timer(any_exec.timer); } if (any_exec.subscription) { - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_executor_execute, static_cast(any_exec.subscription->get_subscription_handle().get())); execute_subscription(any_exec.subscription); @@ -698,7 +698,7 @@ Executor::execute_client( void Executor::wait_for_work(std::chrono::nanoseconds timeout) { - TRACEPOINT(rclcpp_executor_wait_for_work, timeout.count()); + TRACETOOLS_TRACEPOINT(rclcpp_executor_wait_for_work, timeout.count()); { std::lock_guard guard(mutex_); @@ -854,7 +854,7 @@ Executor::get_next_ready_executable_from_map( const rclcpp::memory_strategy::MemoryStrategy::WeakCallbackGroupsToNodesMap & weak_groups_to_nodes) { - TRACEPOINT(rclcpp_executor_get_next_ready); + TRACETOOLS_TRACEPOINT(rclcpp_executor_get_next_ready); bool success = false; std::lock_guard guard{mutex_}; // Check the timers to see if there are any that are ready diff --git a/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp b/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp index d2e821a9e6..f0a2903af4 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_timers.cpp @@ -51,7 +51,7 @@ NodeTimers::add_timer( std::string("failed to notify wait set on timer creation: ") + ex.what()); } - TRACEPOINT( + TRACETOOLS_TRACEPOINT( rclcpp_timer_link_node, static_cast(timer->get_timer_handle().get()), static_cast(node_base_->get_rcl_node_handle())); diff --git a/rclcpp/src/rclcpp/subscription_base.cpp b/rclcpp/src/rclcpp/subscription_base.cpp index e95cb4ac49..a0351b94cc 100644 --- a/rclcpp/src/rclcpp/subscription_base.cpp +++ b/rclcpp/src/rclcpp/subscription_base.cpp @@ -215,7 +215,7 @@ SubscriptionBase::take_type_erased(void * message_out, rclcpp::MessageInfo & mes &message_info_out.get_rmw_message_info(), nullptr // rmw_subscription_allocation_t is unused here ); - TRACEPOINT(rclcpp_take, static_cast(message_out)); + TRACETOOLS_TRACEPOINT(rclcpp_take, static_cast(message_out)); if (RCL_RET_SUBSCRIPTION_TAKE_FAILED == ret) { return false; } else if (RCL_RET_OK != ret) {