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 TRACETOOLS_ prefix for tracepoint-related macros #2162

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 @@ -156,7 +156,7 @@ class AnyServiceCallback
const std::shared_ptr<rmw_request_id_t> & request_header,
std::shared_ptr<typename ServiceT::Request> request)
{
TRACEPOINT(callback_start, static_cast<const void *>(this), false);
TRACETOOLS_TRACEPOINT(callback_start, static_cast<const void *>(this), false);
if (std::holds_alternative<std::monostate>(callback_)) {
// TODO(ivanpauno): Remove the set method, and force the users of this class
// to pass a callback at construnciton.
Expand All @@ -182,7 +182,7 @@ class AnyServiceCallback
const auto & cb = std::get<SharedPtrWithRequestHeaderCallback>(callback_);
cb(request_header, std::move(request), response);
}
TRACEPOINT(callback_end, static_cast<const void *>(this));
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
return response;
}

Expand All @@ -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<const void *>(this),
symbol);
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 @@ -492,7 +492,7 @@ class AnySubscriptionCallback
std::shared_ptr<ROSMessageType> message,
const rclcpp::MessageInfo & message_info)
{
TRACEPOINT(callback_start, static_cast<const void *>(this), false);
TRACETOOLS_TRACEPOINT(callback_start, static_cast<const void *>(this), false);
// Check if the variant is "unset", throw if it is.
if (callback_variant_.index() == 0) {
if (std::get<0>(callback_variant_) == nullptr) {
Expand Down Expand Up @@ -583,7 +583,7 @@ class AnySubscriptionCallback
static_assert(always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACEPOINT(callback_end, static_cast<const void *>(this));
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
}

// Dispatch when input is a serialized message and the output could be anything.
Expand All @@ -592,7 +592,7 @@ class AnySubscriptionCallback
std::shared_ptr<rclcpp::SerializedMessage> serialized_message,
const rclcpp::MessageInfo & message_info)
{
TRACEPOINT(callback_start, static_cast<const void *>(this), false);
TRACETOOLS_TRACEPOINT(callback_start, static_cast<const void *>(this), false);
// Check if the variant is "unset", throw if it is.
if (callback_variant_.index() == 0) {
if (std::get<0>(callback_variant_) == nullptr) {
Expand Down Expand Up @@ -663,15 +663,15 @@ class AnySubscriptionCallback
static_assert(always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACEPOINT(callback_end, static_cast<const void *>(this));
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
}

void
dispatch_intra_process(
std::shared_ptr<const SubscribedType> message,
const rclcpp::MessageInfo & message_info)
{
TRACEPOINT(callback_start, static_cast<const void *>(this), true);
TRACETOOLS_TRACEPOINT(callback_start, static_cast<const void *>(this), true);
// Check if the variant is "unset", throw if it is.
if (callback_variant_.index() == 0) {
if (std::get<0>(callback_variant_) == nullptr) {
Expand Down Expand Up @@ -793,15 +793,15 @@ class AnySubscriptionCallback
static_assert(always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACEPOINT(callback_end, static_cast<const void *>(this));
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
}

void
dispatch_intra_process(
std::unique_ptr<SubscribedType, SubscribedTypeDeleter> message,
const rclcpp::MessageInfo & message_info)
{
TRACEPOINT(callback_start, static_cast<const void *>(this), true);
TRACETOOLS_TRACEPOINT(callback_start, static_cast<const void *>(this), true);
// Check if the variant is "unset", throw if it is.
if (callback_variant_.index() == 0) {
if (std::get<0>(callback_variant_) == nullptr) {
Expand Down Expand Up @@ -927,7 +927,7 @@ class AnySubscriptionCallback
static_assert(always_false_v<T>, "unhandled callback type");
}
}, callback_variant_);
TRACEPOINT(callback_end, static_cast<const void *>(this));
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
}

constexpr
Expand Down Expand Up @@ -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<const void *>(this),
symbol);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ class TypedIntraProcessBuffer : public IntraProcessBuffer<MessageT, Alloc, Messa

buffer_ = std::move(buffer_impl);

TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_buffer_to_ipb,
static_cast<const void *>(buffer_.get()),
static_cast<const void *>(this));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,10 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>
if (capacity == 0) {
throw std::invalid_argument("capacity must be a positive, non-zero value");
}
TRACEPOINT(rclcpp_construct_ring_buffer, static_cast<const void *>(this), capacity_);
TRACETOOLS_TRACEPOINT(
rclcpp_construct_ring_buffer,
static_cast<const void *>(this),
capacity_);
}

virtual ~RingBufferImplementation() {}
Expand All @@ -69,7 +72,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>

write_index_ = next_(write_index_);
ring_buffer_[write_index_] = std::move(request);
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_ring_buffer_enqueue,
static_cast<const void *>(this),
write_index_,
Expand Down Expand Up @@ -98,7 +101,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>
}

auto request = std::move(ring_buffer_[read_index_]);
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_ring_buffer_dequeue,
static_cast<const void *>(this),
read_index_,
Expand Down Expand Up @@ -162,7 +165,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>

void clear()
{
TRACEPOINT(rclcpp_ring_buffer_clear, static_cast<const void *>(this));
TRACETOOLS_TRACEPOINT(rclcpp_ring_buffer_clear, static_cast<const void *>(this));
}

private:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ class SubscriptionIntraProcess
buffer_type),
any_callback_(callback)
{
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_subscription_callback_added,
static_cast<const void *>(this),
static_cast<const void *>(&any_callback_));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ class SubscriptionIntraProcessBuffer : public SubscriptionROSMsgIntraProcessBuff
buffer_type,
qos_profile,
std::make_shared<Alloc>(subscribed_type_allocator_));
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_ipb_to_subscription,
static_cast<const void *>(buffer_.get()),
static_cast<const void *>(this));
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/include/rclcpp/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -421,7 +421,7 @@ class Publisher : public PublisherBase
void
do_inter_process_publish(const ROSMessageType & msg)
{
TRACEPOINT(rclcpp_publish, nullptr, static_cast<const void *>(&msg));
TRACETOOLS_TRACEPOINT(rclcpp_publish, nullptr, static_cast<const void *>(&msg));
auto status = rcl_publish(publisher_handle_.get(), &msg, nullptr);

if (RCL_RET_PUBLISHER_INVALID == status) {
Expand Down Expand Up @@ -484,7 +484,7 @@ class Publisher : public PublisherBase
if (!msg) {
throw std::runtime_error("cannot publish msg which is a null pointer");
}
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_intra_publish,
static_cast<const void *>(publisher_handle_.get()),
msg.get());
Expand All @@ -506,7 +506,7 @@ class Publisher : public PublisherBase
if (!msg) {
throw std::runtime_error("cannot publish msg which is a null pointer");
}
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_intra_publish,
static_cast<const void *>(publisher_handle_.get()),
msg.get());
Expand All @@ -529,7 +529,7 @@ class Publisher : public PublisherBase
if (!msg) {
throw std::runtime_error("cannot publish msg which is a null pointer");
}
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_intra_publish,
static_cast<const void *>(publisher_handle_.get()),
msg.get());
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/service.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -352,7 +352,7 @@ class Service

rclcpp::exceptions::throw_from_rcl_error(ret, "could not create service");
}
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_service_callback_added,
static_cast<const void *>(get_service_handle().get()),
static_cast<const void *>(&any_callback_));
Expand Down Expand Up @@ -387,7 +387,7 @@ class Service
}

service_handle_ = service_handle;
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_service_callback_added,
static_cast<const void *>(get_service_handle().get()),
static_cast<const void *>(&any_callback_));
Expand Down Expand Up @@ -424,7 +424,7 @@ class Service
// In this case, rcl owns the service handle memory
service_handle_ = std::shared_ptr<rcl_service_t>(new rcl_service_t);
service_handle_->impl = service_handle->impl;
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_service_callback_added,
static_cast<const void *>(get_service_handle().get()),
static_cast<const void *>(&any_callback_));
Expand Down
6 changes: 3 additions & 3 deletions rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<const void *>(get_subscription_handle().get()),
static_cast<const void *>(subscription_intra_process_.get()));
Expand All @@ -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<const void *>(get_subscription_handle().get()),
static_cast<const void *>(this));
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_subscription_callback_added,
static_cast<const void *>(this),
static_cast<const void *>(&any_callback_));
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 @@ -223,14 +223,14 @@ class GenericTimer : public TimerBase
)
: TimerBase(clock, period, context), callback_(std::forward<FunctorT>(callback))
{
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_timer_callback_added,
static_cast<const void *>(get_timer_handle().get()),
reinterpret_cast<const void *>(&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<const void *>(&callback_),
symbol);
Expand Down Expand Up @@ -269,9 +269,9 @@ class GenericTimer : public TimerBase
void
execute_callback() override
{
TRACEPOINT(callback_start, reinterpret_cast<const void *>(&callback_), false);
TRACETOOLS_TRACEPOINT(callback_start, reinterpret_cast<const void *>(&callback_), false);
execute_callback_delegate<>();
TRACEPOINT(callback_end, reinterpret_cast<const void *>(&callback_));
TRACETOOLS_TRACEPOINT(callback_end, reinterpret_cast<const void *>(&callback_));
}

// void specialization
Expand Down
8 changes: 4 additions & 4 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -525,13 +525,13 @@ Executor::execute_any_executable(AnyExecutable & any_exec)
return;
}
if (any_exec.timer) {
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_executor_execute,
static_cast<const void *>(any_exec.timer->get_timer_handle().get()));
execute_timer(any_exec.timer);
}
if (any_exec.subscription) {
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rclcpp_executor_execute,
static_cast<const void *>(any_exec.subscription->get_subscription_handle().get()));
execute_subscription(any_exec.subscription);
Expand Down Expand Up @@ -726,7 +726,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<std::mutex> guard(mutex_);

Expand Down Expand Up @@ -882,7 +882,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<std::mutex> guard{mutex_};
// Check the timers to see if there are any that are ready
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/node_interfaces/node_timers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,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<const void *>(timer->get_timer_handle().get()),
static_cast<const void *>(node_base_->get_rcl_node_handle()));
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/subscription_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,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<const void *>(message_out));
TRACETOOLS_TRACEPOINT(rclcpp_take, static_cast<const void *>(message_out));
if (RCL_RET_SUBSCRIPTION_TAKE_FAILED == ret) {
return false;
} else if (RCL_RET_OK != ret) {
Expand Down