Switch to generic 'callback_start|end' event

This commit is contained in:
Christophe Bedard 2019-06-14 10:08:24 +02:00
parent e3f9fa036a
commit 35092f89ff
4 changed files with 83 additions and 178 deletions

View file

@ -65,21 +65,6 @@ void TRACEPOINT(
const void * subscription_handle,
const void * callback);
/**
* tp: rclcpp_subscription_callback_start
*/
void TRACEPOINT(
rclcpp_subscription_callback_start,
const void * callback,
const bool is_intra_process);
/**
* tp: rclcpp_subscription_callback_end
*/
void TRACEPOINT(
rclcpp_subscription_callback_end,
const void * callback);
/**
* tp: rcl_service_init
*/
@ -98,20 +83,6 @@ void TRACEPOINT(
const void * service_handle,
const void * callback);
/**
* tp: rclcpp_service_callback_start
*/
void TRACEPOINT(
rclcpp_service_callback_start,
const void * callback);
/**
* tp: rclcpp_service_callback_end
*/
void TRACEPOINT(
rclcpp_service_callback_end,
const void * callback);
/**
* tp: rcl_client_init
*/
@ -138,20 +109,6 @@ void TRACEPOINT(
const void * timer_handle,
const void * callback);
/**
* tp: rclcpp_timer_callback_start
*/
void TRACEPOINT(
rclcpp_timer_callback_start,
const void * callback);
/**
* tp: rclcpp_timer_callback_end
*/
void TRACEPOINT(
rclcpp_timer_callback_end,
const void * callback);
/**
* tp: rclcpp_callback_register
*/
@ -160,6 +117,29 @@ void TRACEPOINT(
const void * callback,
const char * function_symbol);
/**
* tp: callback_start
*/
void TRACEPOINT(
callback_start,
const void * callback,
const bool is_intra_process);
/**
* tp: callback_start
* (is_intra_process=false)
*/
void TRACEPOINT(
callback_start,
const void * callback);
/**
* tp: callback_end
*/
void TRACEPOINT(
callback_end,
const void * callback);
#ifdef __cplusplus
}
#endif

View file

@ -7,16 +7,14 @@ for event in \
ros2:rcl_publisher_init \
ros2:rcl_subscription_init \
ros2:rclcpp_subscription_callback_added \
ros2:rclcpp_subscription_callback_start \
ros2:rclcpp_subscription_callback_end \
ros2:rcl_service_init \
ros2:rclcpp_service_callback_added \
ros2:rclcpp_service_callback_start \
ros2:rclcpp_service_callback_end \
ros2:rcl_client_init \
ros2:rcl_timer_init \
ros2:rclcpp_timer_callback_added \
ros2:rclcpp_register_callback
ros2:rclcpp_register_callback \
ros2:callback_start \
ros2:callback_end
do
lttng enable-event -c ros2 -u $event
done

View file

@ -79,30 +79,6 @@ TRACEPOINT_EVENT(
)
)
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,
@ -133,28 +109,6 @@ TRACEPOINT_EVENT(
)
)
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,
@ -198,28 +152,6 @@ TRACEPOINT_EVENT(
)
)
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,
@ -232,3 +164,27 @@ TRACEPOINT_EVENT(
ctf_string(symbol, symbol_arg)
)
)
TRACEPOINT_EVENT(
ros2,
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,
callback_end,
TP_ARGS(
const void *, callback_arg
),
TP_FIELDS(
ctf_integer_hex(const void *, callback, callback_arg)
)
)

View file

@ -91,28 +91,6 @@ void TRACEPOINT(
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 * service_handle,
@ -141,26 +119,6 @@ void TRACEPOINT(
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 * client_handle,
@ -201,26 +159,6 @@ void TRACEPOINT(
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 * callback,
@ -232,3 +170,36 @@ void TRACEPOINT(
callback,
function_symbol);
}
void TRACEPOINT(
callback_start,
const void * callback,
const bool is_intra_process)
{
CONDITIONAL_TP(
ros2,
callback_start,
callback,
(is_intra_process ? 1 : 0));
}
void TRACEPOINT(
callback_start,
const void * callback)
{
CONDITIONAL_TP(
ros2,
callback_start,
callback,
0);
}
void TRACEPOINT(
callback_end,
const void * callback)
{
CONDITIONAL_TP(
ros2,
callback_end,
callback);
}