|
tracetools
master
Tracing tools and instrumentation for ROS 2
|
#include <stdint.h>#include <string.h>#include <stdbool.h>#include "tracetools/config.h"#include "tracetools/visibility_control.hpp"
Go to the source code of this file.
Macros | |
| #define | TRACEPOINT(event_name, ...) (ros_trace_ ## event_name)(__VA_ARGS__) |
| Call a tracepoint. More... | |
Functions | |
| bool | ros_trace_compile_status () |
| Get tracing compilation status. More... | |
| void | ros_trace_rcl_init (const void *context_handle) |
rcl_init More... | |
| void | ros_trace_rcl_node_init (const void *node_handle, const void *rmw_handle, const char *node_name, const char *node_namespace) |
rcl_node_init More... | |
| void | ros_trace_rcl_publisher_init (const void *publisher_handle, const void *node_handle, const void *rmw_publisher_handle, const char *topic_name, const size_t queue_depth) |
rcl_publisher_init More... | |
| void | ros_trace_rcl_subscription_init (const void *subscription_handle, const void *node_handle, const void *rmw_subscription_handle, const char *topic_name, const size_t queue_depth) |
rcl_subscription_init More... | |
| void | ros_trace_rclcpp_subscription_init (const void *subscription_handle, const void *subscription) |
rclcpp_subscription_init More... | |
| void | ros_trace_rclcpp_subscription_callback_added (const void *subscription, const void *callback) |
rclcpp_subscription_callback_added More... | |
| void | ros_trace_rcl_service_init (const void *service_handle, const void *node_handle, const void *rmw_service_handle, const char *service_name) |
rcl_service_init More... | |
| void | ros_trace_rclcpp_service_callback_added (const void *service_handle, const void *callback) |
rclcpp_service_callback_added More... | |
| void | ros_trace_rcl_client_init (const void *client_handle, const void *node_handle, const void *rmw_client_handle, const char *service_name) |
rcl_client_init More... | |
| void | ros_trace_rcl_timer_init (const void *timer_handle, int64_t period) |
rcl_timer_init More... | |
| void | ros_trace_rclcpp_timer_callback_added (const void *timer_handle, const void *callback) |
rclcpp_timer_callback_added More... | |
| void | ros_trace_rclcpp_callback_register (const void *callback, const char *function_symbol) |
rclcpp_callback_register More... | |
| void | ros_trace_callback_start (const void *callback, const bool is_intra_process) |
callback_start More... | |
| void | ros_trace_callback_end (const void *callback) |
callback_end More... | |
| #define TRACEPOINT | ( | event_name, | |
| ... | |||
| ) | (ros_trace_ ## event_name)(__VA_ARGS__) |
Call a tracepoint.
This is the preferred method over calling the actual function directly.
| bool ros_trace_compile_status | ( | ) |
Get tracing compilation status.
true if tracing is enabled, false otherwise | void ros_trace_rcl_init | ( | const void * | context_handle | ) |
rcl_init
Initialisation for the whole process. Notes the tracetools version automatically.
| [in] | context_handle | pointer to the rcl_context_t handle |
| void ros_trace_rcl_node_init | ( | const void * | node_handle, |
| const void * | rmw_handle, | ||
| const char * | node_name, | ||
| const char * | node_namespace | ||
| ) |
rcl_node_init
Node initialisation. Links a rcl_node_t handle to its rmw_node_t handle.
| [in] | node_handle | pointer to the node's rcl_node_t handle |
| [in] | rmw_handle | pointer to the node's rmw_node_t handle |
| [in] | node_name | node name |
| [in] | node_namespace | node namespace |
| void ros_trace_rcl_publisher_init | ( | const void * | publisher_handle, |
| const void * | node_handle, | ||
| const void * | rmw_publisher_handle, | ||
| const char * | topic_name, | ||
| const size_t | queue_depth | ||
| ) |
rcl_publisher_init
Publisher initialisation. Links a rcl_publisher_t handle to its rcl_node_t handle and its rmw_publisher_t handle, and links it to a topic name.
| [in] | publisher_handle | pointer to the publisher's rcl_publisher_t handle |
| [in] | node_handle | pointer to the rcl_node_t handle of the node the publisher belongs to |
| [in] | rmw_publisher_handle | pointer to the publisher's rmw_publisher_t handle |
| [in] | topic_name | full topic name |
| [in] | queue_depth | publisher history depth |
| void ros_trace_rcl_subscription_init | ( | const void * | subscription_handle, |
| const void * | node_handle, | ||
| const void * | rmw_subscription_handle, | ||
| const char * | topic_name, | ||
| const size_t | queue_depth | ||
| ) |
rcl_subscription_init
Subscription initialisation. Links a rcl_subscription_t handle to its rcl_node_t handle and its rmw_subscription_t handle, and links it to a topic name.
| [in] | subscription_handle | pointer to the subscription's rcl_subscription_t handle |
| [in] | node_handle | pointer to the rcl_node_t handle of the node the subscription belongs to |
| [in] | rmw_subscription_handle | pointer to the subscription's rmw_subscription_t handle |
| [in] | topic_name | full topic name |
| [in] | queue_depth | subscription history depth |
| void ros_trace_rclcpp_subscription_init | ( | const void * | subscription_handle, |
| const void * | subscription | ||
| ) |
rclcpp_subscription_init
Subscription object initialisation. Links the rclcpp::*Subscription* object to a rcl_subscription_t handle. Needed since there could be more than 1 rclcpp::*Subscription* object for one rcl subscription (e.g. when using intra-process).
| [in] | subscription_handle | pointer to the rcl_subscription_t handle of the subscription this object belongs to |
| [in] | subscription | pointer to this subscription object (e.g. rclcpp::*Subscription*) |
| void ros_trace_rclcpp_subscription_callback_added | ( | const void * | subscription, |
| const void * | callback | ||
| ) |
rclcpp_subscription_callback_added
Link a subscription callback object to a subscription object.
| [in] | subscription | pointer to the subscription object this callback belongs to |
| [in] | callback | pointer to this callback object (e.g. rclcpp::AnySubscriptionCallback) |
| void ros_trace_rcl_service_init | ( | const void * | service_handle, |
| const void * | node_handle, | ||
| const void * | rmw_service_handle, | ||
| const char * | service_name | ||
| ) |
rcl_service_init
Service initialisation. Links a rcl_service_t handle to its rcl_node_t handle and its rmw_service_t handle, and links it to a service name.
| [in] | service_handle | pointer to the service's rcl_service_t handle |
| [in] | node_handle | pointer to the rcl_node_t handle of the node the service belongs to |
| [in] | rmw_service_handle | pointer to the service's rmw_service_t handle |
| [in] | service_name | full service name |
| void ros_trace_rclcpp_service_callback_added | ( | const void * | service_handle, |
| const void * | callback | ||
| ) |
rclcpp_service_callback_added
Link a service callback object to a service.
| [in] | service_handle | pointer to the rcl_service_t handle of the service this callback belongs to |
| [in] | callback | pointer to this callback object (e.g. rclcpp::AnyServiceCallback) |
| void ros_trace_rcl_client_init | ( | const void * | client_handle, |
| const void * | node_handle, | ||
| const void * | rmw_client_handle, | ||
| const char * | service_name | ||
| ) |
rcl_client_init
Client initialisation. Links a rcl_client_t handle to its rcl_node_t handle and its rmw_client_t handle, and links it to a client name.
| [in] | client_handle | pointer to the client's rcl_client_t handle |
| [in] | node_handle | pointer to the rcl_node_t handle of the node the client belongs to |
| [in] | rmw_client_handle | pointer to the client's rmw_client_t handle |
| [in] | service_name | full client name |
| void ros_trace_rcl_timer_init | ( | const void * | timer_handle, |
| int64_t | period | ||
| ) |
rcl_timer_init
Timer initialisation. Notes the timer's period.
| [in] | timer_handle | pointer to the timer's rcl_timer_t handle |
| [in] | period | period in nanoseconds |
| void ros_trace_rclcpp_timer_callback_added | ( | const void * | timer_handle, |
| const void * | callback | ||
| ) |
rclcpp_timer_callback_added
Link a timer callback object to its rcl_timer_t handle.
| [in] | timer_handle | pointer to the rcl_timer_t handle of the timer this callback belongs to |
| [in] | callback | pointer to the callback object (std::function) |
| void ros_trace_rclcpp_callback_register | ( | const void * | callback, |
| const char * | function_symbol | ||
| ) |
rclcpp_callback_register
Register a demangled function symbol with a callback.
| [in] | callback | pointer to the callback object (e.g. rclcpp::AnySubscriptionCallback, rclcpp::AnyServiceCallback, timer std::function, etc.) |
| [in] | function_symbol | demangled symbol of the callback function/lambda, see get_symbol() |
| void ros_trace_callback_start | ( | const void * | callback, |
| const bool | is_intra_process | ||
| ) |
callback_start
Start of a callback.
| [in] | callback | pointer to this callback object (e.g. rclcpp::AnySubscriptionCallback, rclcpp::AnyServiceCallback, timer std::function, etc.) |
| [in] | is_intra_process | whether this callback is done via intra-process or not |
| void ros_trace_callback_end | ( | const void * | callback | ) |
callback_end
End of a callback.
| [in] | callback | pointer to this callback object (e.g. rclcpp::AnySubscriptionCallback, rclcpp::AnyServiceCallback, timer std::function, etc.) |
1.8.17