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 #1058

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
2 changes: 1 addition & 1 deletion rcl/src/rcl/client.c
Original file line number Diff line number Diff line change
Expand Up @@ -176,7 +176,7 @@ rcl_client_init(
client->impl->options = *options;
atomic_init(&client->impl->sequence_number, 0);
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Client initialized");
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rcl_client_init,
(const void *)client,
(const void *)node,
Expand Down
2 changes: 1 addition & 1 deletion rcl/src/rcl/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -312,7 +312,7 @@ rcl_init(
goto fail;
}

TRACEPOINT(rcl_init, (const void *)context);
TRACETOOLS_TRACEPOINT(rcl_init, (const void *)context);

return RCL_RET_OK;
fail:
Expand Down
2 changes: 1 addition & 1 deletion rcl/src/rcl/node.c
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,7 @@ rcl_node_init(
}
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Node initialized");
ret = RCL_RET_OK;
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rcl_node_init,
(const void *)node,
(const void *)rcl_node_get_rmw_handle(node),
Expand Down
4 changes: 2 additions & 2 deletions rcl/src/rcl/publisher.c
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ rcl_publisher_init(
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Publisher initialized");
// context
publisher->impl->context = node->context;
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rcl_publisher_init,
(const void *)publisher,
(const void *)node,
Expand Down Expand Up @@ -258,7 +258,7 @@ rcl_publish(
return RCL_RET_PUBLISHER_INVALID; // error already set
}
RCL_CHECK_ARGUMENT_FOR_NULL(ros_message, RCL_RET_INVALID_ARGUMENT);
TRACEPOINT(rcl_publish, (const void *)publisher, (const void *)ros_message);
TRACETOOLS_TRACEPOINT(rcl_publish, (const void *)publisher, (const void *)ros_message);
if (rmw_publish(publisher->impl->rmw_handle, ros_message, allocation) != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR;
Expand Down
2 changes: 1 addition & 1 deletion rcl/src/rcl/service.c
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@ rcl_service_init(
// options
service->impl->options = *options;
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Service initialized");
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rcl_service_init,
(const void *)service,
(const void *)node,
Expand Down
4 changes: 2 additions & 2 deletions rcl/src/rcl/subscription.c
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ rcl_subscription_init(
subscription->impl->options = *options;
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription initialized");
ret = RCL_RET_OK;
TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rcl_subscription_init,
(const void *)subscription,
(const void *)node,
Expand Down Expand Up @@ -536,7 +536,7 @@ rcl_take(
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Subscription take succeeded: %s", taken ? "true" : "false");
TRACEPOINT(rcl_take, (const void *)ros_message);
TRACETOOLS_TRACEPOINT(rcl_take, (const void *)ros_message);
if (!taken) {
return RCL_RET_SUBSCRIPTION_TAKE_FAILED;
}
Expand Down
2 changes: 1 addition & 1 deletion rcl/src/rcl/timer.c
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ rcl_timer_init(
return RCL_RET_BAD_ALLOC;
}
*timer->impl = impl;
TRACEPOINT(rcl_timer_init, (const void *)timer, period);
TRACETOOLS_TRACEPOINT(rcl_timer_init, (const void *)timer, period);
return RCL_RET_OK;
}

Expand Down
4 changes: 2 additions & 2 deletions rcl_lifecycle/src/rcl_lifecycle.c
Original file line number Diff line number Diff line change
Expand Up @@ -247,7 +247,7 @@ rcl_lifecycle_state_machine_init(
}
}

TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rcl_lifecycle_state_machine_init,
(const void *)node_handle,
(const void *)state_machine);
Expand Down Expand Up @@ -370,7 +370,7 @@ _trigger_transition(
}
}

TRACEPOINT(
TRACETOOLS_TRACEPOINT(
rcl_lifecycle_transition,
(const void *)state_machine,
transition->start->label,
Expand Down