#include TRACEPOINT_EVENT( ros2, rcl_init, TP_ARGS( const void *, context_arg ), TP_FIELDS( ctf_integer_hex(const void *, context, context_arg) ) ) TRACEPOINT_EVENT( ros2, rcl_node_init, TP_ARGS( const void *, node_handle_arg, const void *, rmw_handle_arg, const char *, node_name_arg, const char *, namespace_arg ), TP_FIELDS( ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) ctf_string(node_name, node_name_arg) ctf_string(namespace, namespace_arg) ) ) TRACEPOINT_EVENT( ros2, rcl_publisher_init, TP_ARGS( const void *, node_handle_arg, const void *, rmw_handle_arg, const void *, publisher_handle_arg, const char *, topic_name_arg, const size_t, depth_arg ), TP_FIELDS( ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) ctf_integer_hex(const void *, publisher_handle, publisher_handle_arg) ctf_string(topic_name, topic_name_arg) ctf_integer(const size_t, depth, depth_arg) ) ) TRACEPOINT_EVENT( ros2, rcl_subscription_init, TP_ARGS( const void *, node_handle_arg, const void *, subscription_handle_arg, const void *, rmw_subscription_handle_arg, const char *, topic_name_arg, const size_t, depth_arg ), TP_FIELDS( ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) ctf_integer_hex(const void *, rmw_subscription_handle, rmw_subscription_handle_arg) ctf_string(topic_name, topic_name_arg) ctf_integer(const size_t, depth, depth_arg) ) ) TRACEPOINT_EVENT( ros2, rclcpp_subscription_callback_added, TP_ARGS( const void *, subscription_handle_arg, const void *, callback_arg ), TP_FIELDS( ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) ctf_integer_hex(const void *, callback, callback_arg) ) ) TRACEPOINT_EVENT( ros2, rclcpp_subscription_callback_start, TP_ARGS( const void *, callback_arg, int, is_intra_process_arg ), TP_FIELDS( ctf_integer_hex(const void *, callback, callback_arg) ctf_integer(int, is_intra_process, is_intra_process_arg) ) ) TRACEPOINT_EVENT( ros2, rclcpp_subscription_callback_end, TP_ARGS( const void *, callback_arg ), TP_FIELDS( ctf_integer_hex(const void *, callback, callback_arg) ) ) TRACEPOINT_EVENT( ros2, rcl_service_init, TP_ARGS( const void *, node_handle_arg, const void *, service_handle_arg, const void *, rmw_service_handle_arg, const char *, service_name_arg ), TP_FIELDS( ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, service_handle, service_handle_arg) ctf_integer_hex(const void *, rmw_service_handle, rmw_service_handle_arg) ctf_string(service_name, service_name_arg) ) ) TRACEPOINT_EVENT( ros2, rclcpp_service_callback_added, TP_ARGS( const void *, service_handle_arg, const void *, callback_arg ), TP_FIELDS( ctf_integer_hex(const void *, service_handle, service_handle_arg) ctf_integer_hex(const void *, callback, callback_arg) ) ) TRACEPOINT_EVENT( ros2, rclcpp_service_callback_start, TP_ARGS( const void *, callback_arg ), TP_FIELDS( ctf_integer_hex(const void *, callback, callback_arg) ) ) TRACEPOINT_EVENT( ros2, rclcpp_service_callback_end, TP_ARGS( const void *, callback_arg ), TP_FIELDS( ctf_integer_hex(const void *, callback, callback_arg) ) ) TRACEPOINT_EVENT( ros2, rcl_client_init, TP_ARGS( const void *, node_handle_arg, const void *, client_handle_arg, const void *, rmw_client_handle_arg, const char *, service_name_arg ), TP_FIELDS( ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, client_handle, client_handle_arg) ctf_integer_hex(const void *, rmw_client_handle, rmw_client_handle_arg) ctf_string(service_name, service_name_arg) ) ) TRACEPOINT_EVENT( ros2, rcl_timer_init, TP_ARGS( const void *, timer_handle_arg, long, period_arg ), TP_FIELDS( ctf_integer_hex(const void *, timer_handle, timer_handle_arg) ctf_integer(long, period, period_arg) ) ) TRACEPOINT_EVENT( ros2, rclcpp_timer_callback_added, TP_ARGS( const void *, timer_handle_arg, const void *, callback_arg ), TP_FIELDS( ctf_integer_hex(const void *, timer_handle, timer_handle_arg) ctf_integer_hex(const void *, callback, callback_arg) ) ) TRACEPOINT_EVENT( ros2, rclcpp_timer_callback_start, TP_ARGS( const void *, callback_arg ), TP_FIELDS( ctf_integer_hex(const void *, callback, callback_arg) ) ) TRACEPOINT_EVENT( ros2, rclcpp_timer_callback_end, TP_ARGS( const void *, callback_arg ), TP_FIELDS( ctf_integer_hex(const void *, callback, callback_arg) ) ) TRACEPOINT_EVENT( ros2, rclcpp_callback_register, TP_ARGS( const void *, callback_arg, const char *, symbol_arg ), TP_FIELDS( ctf_integer_hex(const void *, callback, callback_arg) ctf_string(symbol, symbol_arg) ) )