ros2_tracing/tracetools/src/tracetools.c
2019-05-28 14:16:38 +02:00

173 lines
3.8 KiB
C

#include <execinfo.h>
#include "tracetools/tracetools.h"
#if defined(WITH_LTTNG) && !defined(_WIN32)
# include "tp_call.h"
# define CONDITIONAL_TP(...) \
tracepoint(__VA_ARGS__)
#else
# define CONDITIONAL_TP(...)
#endif
const char * get_symbol(const void * function_ptr) {
#if defined(WITH_LTTNG) && !defined(_WIN32)
char** symbols = backtrace_symbols(&function_ptr, 1);
const char * result = symbols[0];
free(symbols);
return result;
#else
return "";
#endif
}
bool ros_trace_compile_status()
{
#if defined(WITH_LTTNG) && !defined(_WIN32)
return true;
#else
return false;
#endif
}
void TRACEPOINT(
rcl_init,
const void * context)
{
CONDITIONAL_TP(ros2, rcl_init, context);
}
void TRACEPOINT(
rcl_node_init,
const void * node_handle,
const void * rmw_handle,
const char * node_name,
const char * node_namespace)
{
CONDITIONAL_TP(ros2, rcl_node_init, node_handle, rmw_handle, node_name, node_namespace);
}
void TRACEPOINT(
rcl_publisher_init,
const void * node_handle,
const void * rmw_handle,
const void * publisher_handle,
const char * topic_name,
const size_t depth)
{
CONDITIONAL_TP(ros2, rcl_publisher_init, node_handle, rmw_handle, publisher_handle, topic_name, depth);
}
void TRACEPOINT(
rcl_subscription_init,
const void * node_handle,
const void * rmw_handle,
const void * subscription_handle,
const char * topic_name,
const size_t depth)
{
CONDITIONAL_TP(ros2, rcl_subscription_init, node_handle, rmw_handle, subscription_handle, topic_name, depth);
}
void TRACEPOINT(
rclcpp_subscription_callback_added,
const void * subscription_handle,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_subscription_callback_added, subscription_handle, callback);
}
void TRACEPOINT(
rclcpp_subscription_callback_start,
const void * callback,
const bool is_intra_process)
{
CONDITIONAL_TP(ros2, rclcpp_subscription_callback_start, callback, (is_intra_process ? 1 : 0));
}
void TRACEPOINT(
rclcpp_subscription_callback_end,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_subscription_callback_end, callback);
}
void TRACEPOINT(
rcl_service_init,
const void * node_handle,
const void * rmw_handle,
const void * service_handle,
const char * service_name)
{
CONDITIONAL_TP(ros2, rcl_service_init, node_handle, rmw_handle, service_handle, service_name);
}
void TRACEPOINT(
rclcpp_service_callback_added,
const void * service_handle,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_service_callback_added, service_handle, callback);
}
void TRACEPOINT(
rclcpp_service_callback_start,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_service_callback_start, callback);
}
void TRACEPOINT(
rclcpp_service_callback_end,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_service_callback_end, callback);
}
void TRACEPOINT(
rcl_client_init,
const void * node_handle,
const void * client_handle,
const void * rmw_client_handle,
const char * service_name)
{
CONDITIONAL_TP(ros2, rcl_client_init, node_handle, client_handle, rmw_client_handle, service_name);
}
void TRACEPOINT(
rcl_timer_init,
const void * timer_handle,
long period)
{
CONDITIONAL_TP(ros2, rcl_timer_init, timer_handle, period);
}
void TRACEPOINT(
rclcpp_timer_callback_added,
const void * timer_handle,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_timer_callback_added, timer_handle, callback);
}
void TRACEPOINT(
rclcpp_timer_callback_start,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_timer_callback_start, callback);
}
void TRACEPOINT(
rclcpp_timer_callback_end,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_timer_callback_end, callback);
}
void TRACEPOINT(
rclcpp_callback_register,
const void * handle,
const void * callback)
{
CONDITIONAL_TP(ros2, rclcpp_callback_register, handle, get_symbol(callback));
}