From 709abe382f4e40390943e9d82097d7e9a5958c78 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 6 Aug 2020 20:08:51 -0400 Subject: [PATCH] Use static_cast instead of C-style cast for instrumentation Signed-off-by: Christophe Bedard --- .../include/rclcpp/any_service_callback.hpp | 8 ++++---- .../rclcpp/any_subscription_callback.hpp | 20 +++++++++---------- .../subscription_intra_process.hpp | 4 ++-- rclcpp/include/rclcpp/service.hpp | 12 +++++------ rclcpp/include/rclcpp/subscription.hpp | 12 +++++------ rclcpp/include/rclcpp/timer.hpp | 10 +++++----- 6 files changed, 33 insertions(+), 33 deletions(-) diff --git a/rclcpp/include/rclcpp/any_service_callback.hpp b/rclcpp/include/rclcpp/any_service_callback.hpp index c6833453cd..86d420860d 100644 --- a/rclcpp/include/rclcpp/any_service_callback.hpp +++ b/rclcpp/include/rclcpp/any_service_callback.hpp @@ -88,7 +88,7 @@ class AnyServiceCallback std::shared_ptr request, std::shared_ptr response) { - TRACEPOINT(callback_start, (const void *)this, false); + TRACEPOINT(callback_start, static_cast(this), false); if (shared_ptr_callback_ != nullptr) { (void)request_header; shared_ptr_callback_(request, response); @@ -97,7 +97,7 @@ class AnyServiceCallback } else { throw std::runtime_error("unexpected request without any callback set"); } - TRACEPOINT(callback_end, (const void *)this); + TRACEPOINT(callback_end, static_cast(this)); } void register_callback_for_tracing() @@ -106,12 +106,12 @@ class AnyServiceCallback if (shared_ptr_callback_) { TRACEPOINT( rclcpp_callback_register, - (const void *)this, + static_cast(this), get_symbol(shared_ptr_callback_)); } else if (shared_ptr_with_request_header_callback_) { TRACEPOINT( rclcpp_callback_register, - (const void *)this, + static_cast(this), get_symbol(shared_ptr_with_request_header_callback_)); } #endif // TRACETOOLS_DISABLED diff --git a/rclcpp/include/rclcpp/any_subscription_callback.hpp b/rclcpp/include/rclcpp/any_subscription_callback.hpp index 6a813c222b..640077a1d9 100644 --- a/rclcpp/include/rclcpp/any_subscription_callback.hpp +++ b/rclcpp/include/rclcpp/any_subscription_callback.hpp @@ -158,7 +158,7 @@ class AnySubscriptionCallback void dispatch( std::shared_ptr message, const rclcpp::MessageInfo & message_info) { - TRACEPOINT(callback_start, (const void *)this, false); + TRACEPOINT(callback_start, static_cast(this), false); if (shared_ptr_callback_) { shared_ptr_callback_(message); } else if (shared_ptr_with_info_callback_) { @@ -178,13 +178,13 @@ class AnySubscriptionCallback } else { throw std::runtime_error("unexpected message without any callback set"); } - TRACEPOINT(callback_end, (const void *)this); + TRACEPOINT(callback_end, static_cast(this)); } void dispatch_intra_process( ConstMessageSharedPtr message, const rclcpp::MessageInfo & message_info) { - TRACEPOINT(callback_start, (const void *)this, true); + TRACEPOINT(callback_start, static_cast(this), true); if (const_shared_ptr_callback_) { const_shared_ptr_callback_(message); } else if (const_shared_ptr_with_info_callback_) { @@ -201,13 +201,13 @@ class AnySubscriptionCallback throw std::runtime_error("unexpected message without any callback set"); } } - TRACEPOINT(callback_end, (const void *)this); + TRACEPOINT(callback_end, static_cast(this)); } void dispatch_intra_process( MessageUniquePtr message, const rclcpp::MessageInfo & message_info) { - TRACEPOINT(callback_start, (const void *)this, true); + TRACEPOINT(callback_start, static_cast(this), true); if (shared_ptr_callback_) { typename std::shared_ptr shared_message = std::move(message); shared_ptr_callback_(shared_message); @@ -225,7 +225,7 @@ class AnySubscriptionCallback } else { throw std::runtime_error("unexpected message without any callback set"); } - TRACEPOINT(callback_end, (const void *)this); + TRACEPOINT(callback_end, static_cast(this)); } bool use_take_shared_method() const @@ -239,22 +239,22 @@ class AnySubscriptionCallback if (shared_ptr_callback_) { TRACEPOINT( rclcpp_callback_register, - (const void *)this, + static_cast(this), get_symbol(shared_ptr_callback_)); } else if (shared_ptr_with_info_callback_) { TRACEPOINT( rclcpp_callback_register, - (const void *)this, + static_cast(this), get_symbol(shared_ptr_with_info_callback_)); } else if (unique_ptr_callback_) { TRACEPOINT( rclcpp_callback_register, - (const void *)this, + static_cast(this), get_symbol(unique_ptr_callback_)); } else if (unique_ptr_with_info_callback_) { TRACEPOINT( rclcpp_callback_register, - (const void *)this, + static_cast(this), get_symbol(unique_ptr_with_info_callback_)); } #endif // TRACETOOLS_DISABLED diff --git a/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp b/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp index 618db3cac1..ee79241fab 100644 --- a/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp +++ b/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp @@ -92,8 +92,8 @@ class SubscriptionIntraProcess : public SubscriptionIntraProcessBase TRACEPOINT( rclcpp_subscription_callback_added, - (const void *)this, - (const void *)&any_callback_); + static_cast(this), + static_cast(&any_callback_)); // The callback object gets copied, so if registration is done too early/before this point // (e.g. in `AnySubscriptionCallback::set()`), its address won't match any address used later // in subsequent tracepoints. diff --git a/rclcpp/include/rclcpp/service.hpp b/rclcpp/include/rclcpp/service.hpp index 094b628987..5c7411892d 100644 --- a/rclcpp/include/rclcpp/service.hpp +++ b/rclcpp/include/rclcpp/service.hpp @@ -223,8 +223,8 @@ class Service : public ServiceBase } TRACEPOINT( rclcpp_service_callback_added, - (const void *)get_service_handle().get(), - (const void *)&any_callback_); + static_cast(get_service_handle().get()), + static_cast(&any_callback_)); #ifndef TRACETOOLS_DISABLED any_callback_.register_callback_for_tracing(); #endif @@ -258,8 +258,8 @@ class Service : public ServiceBase service_handle_ = service_handle; TRACEPOINT( rclcpp_service_callback_added, - (const void *)get_service_handle().get(), - (const void *)&any_callback_); + static_cast(get_service_handle().get()), + static_cast(&any_callback_)); #ifndef TRACETOOLS_DISABLED any_callback_.register_callback_for_tracing(); #endif @@ -295,8 +295,8 @@ class Service : public ServiceBase service_handle_->impl = service_handle->impl; TRACEPOINT( rclcpp_service_callback_added, - (const void *)get_service_handle().get(), - (const void *)&any_callback_); + static_cast(get_service_handle().get()), + static_cast(&any_callback_)); #ifndef TRACETOOLS_DISABLED any_callback_.register_callback_for_tracing(); #endif diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 42bcb26dc8..edc9a444db 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -184,8 +184,8 @@ class Subscription : public SubscriptionBase resolve_intra_process_buffer_type(options.intra_process_buffer_type, callback)); TRACEPOINT( rclcpp_subscription_init, - (const void *)get_subscription_handle().get(), - (const void *)subscription_intra_process.get()); + static_cast(get_subscription_handle().get()), + static_cast(subscription_intra_process.get())); // Add it to the intra process manager. using rclcpp::experimental::IntraProcessManager; @@ -200,12 +200,12 @@ class Subscription : public SubscriptionBase TRACEPOINT( rclcpp_subscription_init, - (const void *)get_subscription_handle().get(), - (const void *)this); + static_cast(get_subscription_handle().get()), + static_cast(this)); TRACEPOINT( rclcpp_subscription_callback_added, - (const void *)this, - (const void *)&any_callback_); + static_cast(this), + static_cast(&any_callback_)); // The callback object gets copied, so if registration is done too early/before this point // (e.g. in `AnySubscriptionCallback::set()`), its address won't match any address used later // in subsequent tracepoints. diff --git a/rclcpp/include/rclcpp/timer.hpp b/rclcpp/include/rclcpp/timer.hpp index 6f0a0ca88e..a2662f4abe 100644 --- a/rclcpp/include/rclcpp/timer.hpp +++ b/rclcpp/include/rclcpp/timer.hpp @@ -176,11 +176,11 @@ class GenericTimer : public TimerBase { TRACEPOINT( rclcpp_timer_callback_added, - (const void *)get_timer_handle().get(), - (const void *)&callback_); + static_cast(get_timer_handle().get()), + static_cast(&callback_)); TRACEPOINT( rclcpp_callback_register, - (const void *)&callback_, + static_cast(&callback_), get_symbol(callback_)); } @@ -205,9 +205,9 @@ class GenericTimer : public TimerBase if (ret != RCL_RET_OK) { throw std::runtime_error("Failed to notify timer that callback occurred"); } - TRACEPOINT(callback_start, (const void *)&callback_, false); + TRACEPOINT(callback_start, static_cast(&callback_), false); execute_callback_delegate<>(); - TRACEPOINT(callback_end, (const void *)&callback_); + TRACEPOINT(callback_end, static_cast(&callback_)); } // void specialization