Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use static_cast instead of C-style cast for instrumentation #1263

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/any_service_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ class AnyServiceCallback
std::shared_ptr<typename ServiceT::Request> request,
std::shared_ptr<typename ServiceT::Response> response)
{
TRACEPOINT(callback_start, (const void *)this, false);
TRACEPOINT(callback_start, static_cast<const void *>(this), false);
if (shared_ptr_callback_ != nullptr) {
(void)request_header;
shared_ptr_callback_(request, response);
Expand All @@ -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<const void *>(this));
}

void register_callback_for_tracing()
Expand All @@ -106,12 +106,12 @@ class AnyServiceCallback
if (shared_ptr_callback_) {
TRACEPOINT(
rclcpp_callback_register,
(const void *)this,
static_cast<const void *>(this),
get_symbol(shared_ptr_callback_));
} else if (shared_ptr_with_request_header_callback_) {
TRACEPOINT(
rclcpp_callback_register,
(const void *)this,
static_cast<const void *>(this),
get_symbol(shared_ptr_with_request_header_callback_));
}
#endif // TRACETOOLS_DISABLED
Expand Down
20 changes: 10 additions & 10 deletions rclcpp/include/rclcpp/any_subscription_callback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ class AnySubscriptionCallback
void dispatch(
std::shared_ptr<MessageT> message, const rclcpp::MessageInfo & message_info)
{
TRACEPOINT(callback_start, (const void *)this, false);
TRACEPOINT(callback_start, static_cast<const void *>(this), false);
if (shared_ptr_callback_) {
shared_ptr_callback_(message);
} else if (shared_ptr_with_info_callback_) {
Expand All @@ -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<const void *>(this));
}

void dispatch_intra_process(
ConstMessageSharedPtr message, const rclcpp::MessageInfo & message_info)
{
TRACEPOINT(callback_start, (const void *)this, true);
TRACEPOINT(callback_start, static_cast<const void *>(this), true);
if (const_shared_ptr_callback_) {
const_shared_ptr_callback_(message);
} else if (const_shared_ptr_with_info_callback_) {
Expand All @@ -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<const void *>(this));
}

void dispatch_intra_process(
MessageUniquePtr message, const rclcpp::MessageInfo & message_info)
{
TRACEPOINT(callback_start, (const void *)this, true);
TRACEPOINT(callback_start, static_cast<const void *>(this), true);
if (shared_ptr_callback_) {
typename std::shared_ptr<MessageT> shared_message = std::move(message);
shared_ptr_callback_(shared_message);
Expand All @@ -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<const void *>(this));
}

bool use_take_shared_method() const
Expand All @@ -239,22 +239,22 @@ class AnySubscriptionCallback
if (shared_ptr_callback_) {
TRACEPOINT(
rclcpp_callback_register,
(const void *)this,
static_cast<const void *>(this),
get_symbol(shared_ptr_callback_));
} else if (shared_ptr_with_info_callback_) {
TRACEPOINT(
rclcpp_callback_register,
(const void *)this,
static_cast<const void *>(this),
get_symbol(shared_ptr_with_info_callback_));
} else if (unique_ptr_callback_) {
TRACEPOINT(
rclcpp_callback_register,
(const void *)this,
static_cast<const void *>(this),
get_symbol(unique_ptr_callback_));
} else if (unique_ptr_with_info_callback_) {
TRACEPOINT(
rclcpp_callback_register,
(const void *)this,
static_cast<const void *>(this),
get_symbol(unique_ptr_with_info_callback_));
}
#endif // TRACETOOLS_DISABLED
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,8 +92,8 @@ class SubscriptionIntraProcess : public SubscriptionIntraProcessBase

TRACEPOINT(
rclcpp_subscription_callback_added,
(const void *)this,
(const void *)&any_callback_);
static_cast<const void *>(this),
static_cast<const void *>(&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.
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<const void *>(get_service_handle().get()),
static_cast<const void *>(&any_callback_));
#ifndef TRACETOOLS_DISABLED
any_callback_.register_callback_for_tracing();
#endif
Expand Down Expand Up @@ -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<const void *>(get_service_handle().get()),
static_cast<const void *>(&any_callback_));
#ifndef TRACETOOLS_DISABLED
any_callback_.register_callback_for_tracing();
#endif
Expand Down Expand Up @@ -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<const void *>(get_service_handle().get()),
static_cast<const void *>(&any_callback_));
#ifndef TRACETOOLS_DISABLED
any_callback_.register_callback_for_tracing();
#endif
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<const void *>(get_subscription_handle().get()),
static_cast<const void *>(subscription_intra_process.get()));

// Add it to the intra process manager.
using rclcpp::experimental::IntraProcessManager;
Expand All @@ -200,12 +200,12 @@ class Subscription : public SubscriptionBase

TRACEPOINT(
rclcpp_subscription_init,
(const void *)get_subscription_handle().get(),
(const void *)this);
static_cast<const void *>(get_subscription_handle().get()),
static_cast<const void *>(this));
TRACEPOINT(
rclcpp_subscription_callback_added,
(const void *)this,
(const void *)&any_callback_);
static_cast<const void *>(this),
static_cast<const void *>(&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.
Expand Down
10 changes: 5 additions & 5 deletions rclcpp/include/rclcpp/timer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,11 +176,11 @@ class GenericTimer : public TimerBase
{
TRACEPOINT(
rclcpp_timer_callback_added,
(const void *)get_timer_handle().get(),
(const void *)&callback_);
static_cast<const void *>(get_timer_handle().get()),
static_cast<const void *>(&callback_));
TRACEPOINT(
rclcpp_callback_register,
(const void *)&callback_,
static_cast<const void *>(&callback_),
get_symbol(callback_));
}

Expand All @@ -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<const void *>(&callback_), false);
execute_callback_delegate<>();
TRACEPOINT(callback_end, (const void *)&callback_);
TRACEPOINT(callback_end, static_cast<const void *>(&callback_));
}

// void specialization
Expand Down