Skip to content

Commit 4efc052

Browse files
Use TRACETOOLS_ prefix for tracepoint-related macros (#2162)
Signed-off-by: Christophe Bedard <[email protected]>
1 parent dab9c8a commit 4efc052

13 files changed

+45
-42
lines changed

rclcpp/include/rclcpp/any_service_callback.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -156,7 +156,7 @@ class AnyServiceCallback
156156
const std::shared_ptr<rmw_request_id_t> & request_header,
157157
std::shared_ptr<typename ServiceT::Request> request)
158158
{
159-
TRACEPOINT(callback_start, static_cast<const void *>(this), false);
159+
TRACETOOLS_TRACEPOINT(callback_start, static_cast<const void *>(this), false);
160160
if (std::holds_alternative<std::monostate>(callback_)) {
161161
// TODO(ivanpauno): Remove the set method, and force the users of this class
162162
// to pass a callback at construnciton.
@@ -182,7 +182,7 @@ class AnyServiceCallback
182182
const auto & cb = std::get<SharedPtrWithRequestHeaderCallback>(callback_);
183183
cb(request_header, std::move(request), response);
184184
}
185-
TRACEPOINT(callback_end, static_cast<const void *>(this));
185+
TRACETOOLS_TRACEPOINT(callback_end, static_cast<const void *>(this));
186186
return response;
187187
}
188188

@@ -191,9 +191,9 @@ class AnyServiceCallback
191191
#ifndef TRACETOOLS_DISABLED
192192
std::visit(
193193
[this](auto && arg) {
194-
if (TRACEPOINT_ENABLED(rclcpp_callback_register)) {
194+
if (TRACETOOLS_TRACEPOINT_ENABLED(rclcpp_callback_register)) {
195195
char * symbol = tracetools::get_symbol(arg);
196-
DO_TRACEPOINT(
196+
TRACETOOLS_DO_TRACEPOINT(
197197
rclcpp_callback_register,
198198
static_cast<const void *>(this),
199199
symbol);

rclcpp/include/rclcpp/any_subscription_callback.hpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -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);

rclcpp/include/rclcpp/experimental/buffers/intra_process_buffer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,7 @@ class TypedIntraProcessBuffer : public IntraProcessBuffer<MessageT, Alloc, Messa
9696

9797
buffer_ = std::move(buffer_impl);
9898

99-
TRACEPOINT(
99+
TRACETOOLS_TRACEPOINT(
100100
rclcpp_buffer_to_ipb,
101101
static_cast<const void *>(buffer_.get()),
102102
static_cast<const void *>(this));

rclcpp/include/rclcpp/experimental/buffers/ring_buffer_implementation.hpp

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,10 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>
5252
if (capacity == 0) {
5353
throw std::invalid_argument("capacity must be a positive, non-zero value");
5454
}
55-
TRACEPOINT(rclcpp_construct_ring_buffer, static_cast<const void *>(this), capacity_);
55+
TRACETOOLS_TRACEPOINT(
56+
rclcpp_construct_ring_buffer,
57+
static_cast<const void *>(this),
58+
capacity_);
5659
}
5760

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

7073
write_index_ = next_(write_index_);
7174
ring_buffer_[write_index_] = std::move(request);
72-
TRACEPOINT(
75+
TRACETOOLS_TRACEPOINT(
7376
rclcpp_ring_buffer_enqueue,
7477
static_cast<const void *>(this),
7578
write_index_,
@@ -98,7 +101,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>
98101
}
99102

100103
auto request = std::move(ring_buffer_[read_index_]);
101-
TRACEPOINT(
104+
TRACETOOLS_TRACEPOINT(
102105
rclcpp_ring_buffer_dequeue,
103106
static_cast<const void *>(this),
104107
read_index_,
@@ -162,7 +165,7 @@ class RingBufferImplementation : public BufferImplementationBase<BufferT>
162165

163166
void clear()
164167
{
165-
TRACEPOINT(rclcpp_ring_buffer_clear, static_cast<const void *>(this));
168+
TRACETOOLS_TRACEPOINT(rclcpp_ring_buffer_clear, static_cast<const void *>(this));
166169
}
167170

168171
private:

rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,7 @@ class SubscriptionIntraProcess
8787
buffer_type),
8888
any_callback_(callback)
8989
{
90-
TRACEPOINT(
90+
TRACETOOLS_TRACEPOINT(
9191
rclcpp_subscription_callback_added,
9292
static_cast<const void *>(this),
9393
static_cast<const void *>(&any_callback_));

rclcpp/include/rclcpp/experimental/subscription_intra_process_buffer.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -93,7 +93,7 @@ class SubscriptionIntraProcessBuffer : public SubscriptionROSMsgIntraProcessBuff
9393
buffer_type,
9494
qos_profile,
9595
std::make_shared<Alloc>(subscribed_type_allocator_));
96-
TRACEPOINT(
96+
TRACETOOLS_TRACEPOINT(
9797
rclcpp_ipb_to_subscription,
9898
static_cast<const void *>(buffer_.get()),
9999
static_cast<const void *>(this));

rclcpp/include/rclcpp/publisher.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -421,7 +421,7 @@ class Publisher : public PublisherBase
421421
void
422422
do_inter_process_publish(const ROSMessageType & msg)
423423
{
424-
TRACEPOINT(rclcpp_publish, nullptr, static_cast<const void *>(&msg));
424+
TRACETOOLS_TRACEPOINT(rclcpp_publish, nullptr, static_cast<const void *>(&msg));
425425
auto status = rcl_publish(publisher_handle_.get(), &msg, nullptr);
426426

427427
if (RCL_RET_PUBLISHER_INVALID == status) {
@@ -484,7 +484,7 @@ class Publisher : public PublisherBase
484484
if (!msg) {
485485
throw std::runtime_error("cannot publish msg which is a null pointer");
486486
}
487-
TRACEPOINT(
487+
TRACETOOLS_TRACEPOINT(
488488
rclcpp_intra_publish,
489489
static_cast<const void *>(publisher_handle_.get()),
490490
msg.get());
@@ -506,7 +506,7 @@ class Publisher : public PublisherBase
506506
if (!msg) {
507507
throw std::runtime_error("cannot publish msg which is a null pointer");
508508
}
509-
TRACEPOINT(
509+
TRACETOOLS_TRACEPOINT(
510510
rclcpp_intra_publish,
511511
static_cast<const void *>(publisher_handle_.get()),
512512
msg.get());
@@ -529,7 +529,7 @@ class Publisher : public PublisherBase
529529
if (!msg) {
530530
throw std::runtime_error("cannot publish msg which is a null pointer");
531531
}
532-
TRACEPOINT(
532+
TRACETOOLS_TRACEPOINT(
533533
rclcpp_intra_publish,
534534
static_cast<const void *>(publisher_handle_.get()),
535535
msg.get());

rclcpp/include/rclcpp/service.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -352,7 +352,7 @@ class Service
352352

353353
rclcpp::exceptions::throw_from_rcl_error(ret, "could not create service");
354354
}
355-
TRACEPOINT(
355+
TRACETOOLS_TRACEPOINT(
356356
rclcpp_service_callback_added,
357357
static_cast<const void *>(get_service_handle().get()),
358358
static_cast<const void *>(&any_callback_));
@@ -387,7 +387,7 @@ class Service
387387
}
388388

389389
service_handle_ = service_handle;
390-
TRACEPOINT(
390+
TRACETOOLS_TRACEPOINT(
391391
rclcpp_service_callback_added,
392392
static_cast<const void *>(get_service_handle().get()),
393393
static_cast<const void *>(&any_callback_));
@@ -424,7 +424,7 @@ class Service
424424
// In this case, rcl owns the service handle memory
425425
service_handle_ = std::shared_ptr<rcl_service_t>(new rcl_service_t);
426426
service_handle_->impl = service_handle->impl;
427-
TRACEPOINT(
427+
TRACETOOLS_TRACEPOINT(
428428
rclcpp_service_callback_added,
429429
static_cast<const void *>(get_service_handle().get()),
430430
static_cast<const void *>(&any_callback_));

rclcpp/include/rclcpp/subscription.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -185,7 +185,7 @@ class Subscription : public SubscriptionBase
185185
this->get_topic_name(), // important to get like this, as it has the fully-qualified name
186186
qos_profile,
187187
resolve_intra_process_buffer_type(options_.intra_process_buffer_type, callback));
188-
TRACEPOINT(
188+
TRACETOOLS_TRACEPOINT(
189189
rclcpp_subscription_init,
190190
static_cast<const void *>(get_subscription_handle().get()),
191191
static_cast<const void *>(subscription_intra_process_.get()));
@@ -201,11 +201,11 @@ class Subscription : public SubscriptionBase
201201
this->subscription_topic_statistics_ = std::move(subscription_topic_statistics);
202202
}
203203

204-
TRACEPOINT(
204+
TRACETOOLS_TRACEPOINT(
205205
rclcpp_subscription_init,
206206
static_cast<const void *>(get_subscription_handle().get()),
207207
static_cast<const void *>(this));
208-
TRACEPOINT(
208+
TRACETOOLS_TRACEPOINT(
209209
rclcpp_subscription_callback_added,
210210
static_cast<const void *>(this),
211211
static_cast<const void *>(&any_callback_));

rclcpp/include/rclcpp/timer.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -223,14 +223,14 @@ class GenericTimer : public TimerBase
223223
)
224224
: TimerBase(clock, period, context), callback_(std::forward<FunctorT>(callback))
225225
{
226-
TRACEPOINT(
226+
TRACETOOLS_TRACEPOINT(
227227
rclcpp_timer_callback_added,
228228
static_cast<const void *>(get_timer_handle().get()),
229229
reinterpret_cast<const void *>(&callback_));
230230
#ifndef TRACETOOLS_DISABLED
231-
if (TRACEPOINT_ENABLED(rclcpp_callback_register)) {
231+
if (TRACETOOLS_TRACEPOINT_ENABLED(rclcpp_callback_register)) {
232232
char * symbol = tracetools::get_symbol(callback_);
233-
DO_TRACEPOINT(
233+
TRACETOOLS_DO_TRACEPOINT(
234234
rclcpp_callback_register,
235235
reinterpret_cast<const void *>(&callback_),
236236
symbol);
@@ -269,9 +269,9 @@ class GenericTimer : public TimerBase
269269
void
270270
execute_callback() override
271271
{
272-
TRACEPOINT(callback_start, reinterpret_cast<const void *>(&callback_), false);
272+
TRACETOOLS_TRACEPOINT(callback_start, reinterpret_cast<const void *>(&callback_), false);
273273
execute_callback_delegate<>();
274-
TRACEPOINT(callback_end, reinterpret_cast<const void *>(&callback_));
274+
TRACETOOLS_TRACEPOINT(callback_end, reinterpret_cast<const void *>(&callback_));
275275
}
276276

277277
// void specialization

0 commit comments

Comments
 (0)