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

fix: node filter improvement #280

Merged
merged 49 commits into from
Apr 25, 2024
Merged
Show file tree
Hide file tree
Changes from 32 commits
Commits
Show all changes
49 commits
Select commit Hold shift + click to select a range
cf4201f
add environment variable CARET_IGNORE_PROCESSES.
xygyo77 Mar 6, 2024
bb9164e
add CARET_IGNORE_PROCESSES environment variable
xygyo77 Mar 7, 2024
d24f44b
fixed
xygyo77 Mar 7, 2024
ac9e470
ci(pre-commit): autofix
pre-commit-ci[bot] Mar 7, 2024
520ab39
PR Review Reflection
xygyo77 Mar 11, 2024
70fbecd
ci(pre-commit): autofix
pre-commit-ci[bot] Mar 11, 2024
65b9685
Changed usage of std::unoderd_map in tracing_controller.cpp.
xygyo77 Mar 20, 2024
f6c1cfd
The node_ptr of the function rclcpp::Executor::add_callback_group_to_…
xygyo77 Mar 20, 2024
8769ea4
for debugging version
xygyo77 Mar 20, 2024
6a76b99
insert debugging code
xygyo77 Mar 21, 2024
0d50809
under review
xygyo77 Mar 25, 2024
01d4676
fixed
xygyo77 Mar 25, 2024
9a4f626
add cache clear
xygyo77 Mar 25, 2024
22b6fd6
allowed_callbacks_ maintenance
xygyo77 Mar 26, 2024
eb44de6
fixed
xygyo77 Mar 26, 2024
db917f7
add debug code
xygyo77 Mar 28, 2024
dd8b5b1
modify debug code
xygyo77 Apr 1, 2024
46034d4
modify debug code
xygyo77 Apr 1, 2024
4482934
fixed review results
xygyo77 Apr 3, 2024
25b9472
fixed
xygyo77 Apr 4, 2024
e5fc047
fixed
xygyo77 Apr 5, 2024
a3facf0
fixed
xygyo77 Apr 8, 2024
59549df
merge main
xygyo77 Apr 9, 2024
ec8d50c
add subscription_to_subscription_handles_
xygyo77 Apr 9, 2024
8f174b1
add message_construct filter
xygyo77 Apr 10, 2024
8a17896
fixed
xygyo77 Apr 11, 2024
44ed3a5
remove debug codes
xygyo77 Apr 12, 2024
ccb8fda
ci(pre-commit): autofix
pre-commit-ci[bot] Apr 12, 2024
b634593
Fixed omission of experimental code deletion.
xygyo77 Apr 12, 2024
c371c25
ci(pre-commit): autofix
pre-commit-ci[bot] Apr 12, 2024
5140fa7
spelling correction
xygyo77 Apr 15, 2024
762946f
Merge branch 'fix/node_filter' of github.com:xygyo77/caret_trace into…
xygyo77 Apr 15, 2024
a211485
Update CARET_trace/src/ros_trace_points.cpp
xygyo77 Apr 16, 2024
e2abdcd
Update CARET_trace/include/caret_trace/tracing_controller.hpp
xygyo77 Apr 16, 2024
55fe808
remove debug code
xygyo77 Apr 16, 2024
146d4e2
Merge branch 'fix/node_filter' of github.com:xygyo77/caret_trace into…
xygyo77 Apr 16, 2024
99b9c1d
Update CARET_trace/include/caret_trace/tracing_controller.hpp
xygyo77 Apr 16, 2024
1aca5df
Merge branch 'fix/node_filter' of github.com:xygyo77/caret_trace into…
xygyo77 Apr 16, 2024
26d5540
Delete unnecessary codes.
xygyo77 Apr 16, 2024
cd38f19
Correction by review.
xygyo77 Apr 16, 2024
11370f1
Correction by review.
xygyo77 Apr 16, 2024
c183502
Suppress /rosout output after /iron.
xygyo77 Apr 16, 2024
4fa8dc7
ci(pre-commit): autofix
pre-commit-ci[bot] Apr 16, 2024
d1e5b38
Update CARET_trace/include/caret_trace/data_container.hpp
xygyo77 Apr 16, 2024
95e0785
fixed debug message
xygyo77 Apr 16, 2024
14c7518
improve message construct
xygyo77 Apr 19, 2024
b359077
modify is_allowed_message()
xygyo77 Apr 23, 2024
6dfffdf
ci(pre-commit): autofix
pre-commit-ci[bot] Apr 23, 2024
9916bc3
Update CARET_trace/include/caret_trace/tracing_controller.hpp
xygyo77 Apr 24, 2024
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
7 changes: 4 additions & 3 deletions CARET_trace/include/caret_trace/data_container.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@
/// @return True if record has finished, false otherwise.
virtual bool record(uint64_t loop_count = 1) = 0;

/// @brief transitionto recording state.
/// @brief transitiont recording state.

Check warning on line 39 in CARET_trace/include/caret_trace/data_container.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (transitiont)
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
virtual void start_recording() = 0;

/// @brief Reset recording state.
Expand All @@ -48,11 +48,12 @@
{
public:
/// @brief for add_callback_group trace points.
using AddCallbackGroup = ContainerTraits<const void *, const void *, const char *, int64_t>;
using AddCallbackGroup =
ContainerTraits<const void *, const void *, const char *, const void *, int64_t>;

/// @brief ContainerTraits for add_callback_group_static_executor trace points.
using AddCallbackGroupStaticExecutor =
ContainerTraits<const void *, const void *, const char *, int64_t>;
ContainerTraits<const void *, const void *, const char *, const void *, int64_t>;

/// @brief ContainerTraits for callback_group_add_client trace points.
using CallbackGroupAddClient = ContainerTraits<const void *, const void *, int64_t>;
Expand Down
77 changes: 72 additions & 5 deletions CARET_trace/include/caret_trace/tracing_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@

/// @brief Classes that implement trace filtering functions such as CARET_SELECT_NODES.
/// @details Reads the environment variables CARET_SELECT_NODES,
/// CARET_IGNORE_NODES, CARET_SELECT_TOPICS, and CARET_IGNORE_TOPICS.
/// CARET_IGNORE_NODES, CARET_SELECT_TOPICS, CARET_IGNORE_TOPICS, and CARET_IGNORE_NODES.
/// Tracepoints related to the specified node name or topic name are filtered
/// so that they are not recorded by LTTng.
/// If both SELECT and IGNORE are specified, SELECT takes priority.
Expand All @@ -38,6 +38,8 @@ class TracingController
/// @param node_name Node name.
void add_node(const void * node_handle, std::string node_name);

std::string get_node_name(const std::string type, const void * key);
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved

/// @brief Register topic name for rcl_subscription_init hook.
/// @param node_handle Address of the node handle.
/// @param subscription_handle Address of the subscription handle.
Expand All @@ -53,19 +55,19 @@ class TracingController
const void * node_handle, const void * rmw_subscription_handle, std::string topic_name);

/// @brief Register binding information for rclcpp_subscription_init tracepoint hook.
/// @param subscription_handle Address of the subscription handle.
/// @param subscription Address of subscription instance.
void add_subscription(const void * subscription_handle, const void * subscription);
/// @param subscription_handle Address of the subscription handle.
void add_subscription(const void * subscription, const void * subscription_handle);

/// @brief Register binding information for rclcpp_subscription_callback_added tracepoint hook.
/// @param subscription Address of subscription instance.
/// @param callback Address of callback instance.
void add_subscription_callback(const void * subscription, const void * callback);

/// @brief Register binding information for rclcpp_timer_link_node tracepoint hook.
/// @param node_handle Address of the node handle.
/// @param timer_handle Address of the timer handle.
void add_timer_handle(const void * node_handle, const void * timer_handle);
/// @param node_handle Address of the node handle.
void add_timer_handle(const void * timer_handle, const void * node_handle);

/// @brief Register topic name for ros_trace_rcl_publisher_init
/// @param node_handle Address of the node handle.
Expand All @@ -89,6 +91,26 @@ class TracingController
/// @param subscription Address of the subscription instance.
void add_ipb(const void * ipb, const void * subscription);

/// @brief Register binding information for rcl_lifecycle_state_machine_init tracepoint.
/// @param state_machine Address of the lifecycle state machine.
/// @param node_handle Address of the node handle.
void add_state_machine(const void * state_machine, const void * node_handle);

/// @brief Register binding information for rclcpp_service_callback_added tracepoint.
/// @param service_handle Address of the service handle.
/// @param node_handle Address of the node handle instance.
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
void add_service_handle(const void * service_handle, const void * node_handle);

/// @brief Register binding information for rcl_client_init tracepoint.
/// @param client_handle Address of the client handle.
/// @param node_handle Address of the node handle instance.
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
void add_client_handle(const void * client_handle, const void * node_handle);

/// @brief Register binding information for intra message tracepoint.
/// @param message Address of the intra original message.
/// @param publisher_handle publisher_handle Address of the publisher handle.
void add_message_publisher_handle(const void * message, const void * publisher_handle);

/// @brief Check if trace point is a enabled callback
/// @param callback
/// @param callback Address of callback instance.
Expand Down Expand Up @@ -124,6 +146,37 @@ class TracingController
/// @return True if the process is enabled, false otherwise.
bool is_allowed_process();

/// @brief Check if trace point is a enabled node
/// @param timer_handle Address of the timer handle.
/// @param callback Address of the callback.
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
/// @return True if the timer_handle is enabled, false otherwise.
bool is_allowed_timer_handle(const void * timer_handle);
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved

/// @brief Check if trace point is a enabled node
/// @param state_machine Address of the lifecycle state machine.
/// @return True if the state_machine is enabled, false otherwise.
bool is_allowed_state_machine(const void * state_machine);

/// @brief Check if trace point is a enabled subscription
/// @param buffer Address of the intra-process buffer.
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
/// @return True if the buffer is enabled, false otherwise.
bool is_allowed_ipb(const void * ipb);
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved

/// @brief Check if trace point is a enabled callback
/// @param service_handle Address of the service handle.
/// @return True if the buffer is enabled, false otherwise.
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
bool is_allowed_service_handle(const void * service_handle);

/// @brief Check if trace point is a enabled callback
/// @param client_handle Address of the client handle.
/// @return True if the buffer is enabled, false otherwise.
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
bool is_allowed_client_handle(const void * client_handle);

/// @brief Check if trace point is a enabled message
/// @param publisher_handle Address of the publisher handle.
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
/// @return True if the message is enabled, false otherwise.
bool is_allowed_message(const void * message);

private:
void debug(std::string message) const;
void info(std::string message) const;
Expand All @@ -149,6 +202,7 @@ class TracingController
std::unordered_map<const void *, std::string> subscription_handle_to_topic_names_;
std::unordered_map<const void *, const void *> subscription_to_subscription_handles_;
std::unordered_map<const void *, const void *> callback_to_subscriptions_;
std::unordered_map<const void *, const void *> subscription_to_callbacks_;

std::unordered_map<const void *, const void *> rmw_subscription_handle_to_node_handles_;
std::unordered_map<const void *, std::string> rmw_subscription_handle_to_topic_names_;
Expand All @@ -158,6 +212,7 @@ class TracingController
std::unordered_map<const void *, const void *> callback_to_timer_handles_;
std::unordered_map<const void *, const void *> timer_handle_to_node_handles_;
std::unordered_map<const void *, bool> allowed_callbacks_;
std::unordered_map<const void *, bool> allowed_timer_handles_;

std::unordered_map<const void *, const void *> publisher_handle_to_node_handles_;
std::unordered_map<const void *, std::string> publisher_handle_to_topic_names_;
Expand All @@ -166,6 +221,18 @@ class TracingController
std::unordered_map<const void *, const void *> buffer_to_ipbs_;
std::unordered_map<const void *, const void *> ipb_to_subscriptions_;
std::unordered_map<const void *, bool> allowed_buffers_;
std::unordered_map<const void *, bool> allowed_ipbs_;

std::unordered_map<const void *, const void *> state_machine_to_node_handles_;
std::unordered_map<const void *, bool> allowed_state_machines_;

std::unordered_map<const void *, const void *> service_handle_to_node_handles_;
std::unordered_map<const void *, bool> allowed_service_handle_;
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
std::unordered_map<const void *, const void *> client_handle_to_node_handles_;
std::unordered_map<const void *, bool> allowed_client_handles_;

std::unordered_map<const void *, const void *> message_to_publisher_handles_;
std::unordered_map<const void *, bool> allowed_messages_;
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
};

#endif // CARET_TRACE__TRACING_CONTROLLER_HPP_
Expand Down
89 changes: 58 additions & 31 deletions CARET_trace/src/hooked_trace_points.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -262,11 +262,13 @@
return dds_return;
}

if (context.is_recording_allowed()) {
if (context.is_recording_allowed() && trace_filter_is_rcl_publish_recorded) {
tracepoint(
TRACEPOINT_PROVIDER, dds_bind_addr_to_stamp, serialized_message_addr, dinp->timestamp.v);
#ifdef DEBUG_OUTPUT
std::cerr << "dds_bind_addr_to_stamp," << data << "," << tstamp << std::endl;
// std::cerr << "dds_bind_addr_to_stamp," << data << "," << tstamp << std::endl;
std::cerr << "dds_bind_addr_to_stamp," << serialized_message_addr << "," << dinp->timestamp.v
<< std::endl;
xygyo77 marked this conversation as resolved.
Show resolved Hide resolved
#endif
}
return dds_return;
Expand All @@ -278,7 +280,6 @@
void * obj, eprosima::fastrtps::rtps::CacheChange_t * change)
{
static auto & context = Singleton<Context>::get_instance();

using functionT = void (*)(void *, eprosima::fastrtps::rtps::CacheChange_t *);
if (FASTDDS::SET_FRAGMENTS == nullptr) {
update_dds_function_addr();
Expand All @@ -289,7 +290,7 @@
return;
}

if (context.is_recording_allowed()) {
if (context.is_recording_allowed() && trace_filter_is_rcl_publish_recorded) {
tracepoint(
TRACEPOINT_PROVIDER, dds_bind_addr_to_stamp, nullptr, change->sourceTimestamp.to_ns());
#ifdef DEBUG_OUTPUT
Expand All @@ -312,7 +313,7 @@
}

// rclcpp::executors::SingleThreadedExecutor::SingleThreadedExecutor(rclcpp::ExecutorOptions const&)
void _ZN6rclcpp9executors22SingleThreadedExecutorC1ERKNS_15ExecutorOptionsE(

Check warning on line 316 in CARET_trace/src/hooked_trace_points.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (ERKNS)
void * obj, const void * option)
{
static void * orig_func = dlsym(RTLD_NEXT, __func__);
Expand Down Expand Up @@ -349,7 +350,7 @@
// std::chrono::duration<long, std::ratio<1l, 1000000000l> >)
void SYMBOL_CONCAT_2(
_ZN6rclcpp9executors21MultiThreadedExecutor,
C1ERKNS_15ExecutorOptionsEmbNSt6chrono8durationIlSt5ratioILl1ELl1000000000EEEE)(

Check warning on line 353 in CARET_trace/src/hooked_trace_points.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (ERKNS)
void * obj, const void * option, size_t number_of_thread, bool yield_before_execute,
const void * timeout)
{
Expand Down Expand Up @@ -384,7 +385,7 @@

// rclcpp::executors::StaticSingleThreadedExecutor::StaticSingleThreadedExecutor(
// rclcpp::ExecutorOptions const&)
void _ZN6rclcpp9executors28StaticSingleThreadedExecutorC1ERKNS_15ExecutorOptionsE(

Check warning on line 388 in CARET_trace/src/hooked_trace_points.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (ERKNS)
void * obj, const void * option)
{
static void * orig_func = dlsym(RTLD_NEXT, __func__);
Expand Down Expand Up @@ -421,7 +422,7 @@
}

auto entities_collector_ptr = static_cast<const void *>(exec_ptr->entities_collector_.get());
data_container.store_add_callback_group_static_executor(
data_container.store_construct_static_executor(
obj, entities_collector_ptr, "static_single_threaded_executor", now);
record(obj, entities_collector_ptr, "static_single_threaded_executor", now);
}
Expand All @@ -439,28 +440,35 @@
_ZN6rclcpp8Executor25add_callback_group_to_map,
ESt10shared_ptrINS_13CallbackGroupEES1_INS_15node_interfaces17NodeBaseInterface,
EERSt3mapISt8weak_ptrIS2_ES8_IS5_ESt10owner_lessIS9_ESaISt4pairIKS9_SA_EEEb)(
void * obj, rclcpp::CallbackGroup::SharedPtr group_ptr, const void * node_ptr,
const void * weak_groups_to_nodes, bool notify)
void * obj, rclcpp::CallbackGroup::SharedPtr group_ptr,
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, const void * weak_groups_to_nodes,
bool notify)
{
static void * orig_func = dlsym(RTLD_NEXT, __func__);
static auto & context = Singleton<Context>::get_instance();
static auto & clock = context.get_clock();
static auto & data_container = context.get_data_container();
static auto record =
[](const void * obj, const void * group_addr, const char * group_type_name, int64_t init_time) {
tracepoint(
TRACEPOINT_PROVIDER, add_callback_group, obj, group_addr, group_type_name, init_time);
static auto record = [](
const void * obj, const void * group_addr, const char * group_type_name,
const void * node_handle, int64_t init_time) {
if (!context.get_controller().is_allowed_node(node_handle)) {
return;
}
tracepoint(
TRACEPOINT_PROVIDER, add_callback_group, obj, group_addr, group_type_name, init_time);

#ifdef DEBUG_OUTPUT
std::cerr << "add_callback_group," << obj << "," << group_addr << "," << group_type_name
<< std::endl;
std::cerr << "add_callback_group," << obj << "," << group_addr << "," << group_type_name
<< std::endl;
#endif
};
};
auto now = clock.now();

using functionT =
void (*)(void *, rclcpp::CallbackGroup::SharedPtr, const void *, const void *, bool);
using functionT = void (*)(
void *, rclcpp::CallbackGroup::SharedPtr, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr,
const void *, bool);
auto group_addr = static_cast<const void *>(group_ptr.get());
auto node_addr = static_cast<const void *>(node_ptr.get());

((functionT)orig_func)(obj, group_ptr, node_ptr, weak_groups_to_nodes, notify);

Expand All @@ -474,8 +482,8 @@

static KeysSet<void *, void *, void *> recorded_args;

auto node_ptr_ = const_cast<void *>(node_ptr);
auto group_addr_ = const_cast<void *>(group_addr);
auto node_addr_ = const_cast<void *>(node_addr);

std::string group_type_name = "unknown";
auto group_type = group_ptr->type();
Expand All @@ -485,18 +493,20 @@
group_type_name = "reentrant";
}

data_container.store_add_callback_group(obj, group_addr, group_type_name.c_str(), now);
if (!recorded_args.has(obj, group_addr_, node_ptr_)) {
recorded_args.insert(obj, group_addr_, node_ptr_);
auto node_handle = static_cast<const void *>(node_ptr->get_rcl_node_handle());
data_container.store_add_callback_group(
obj, group_addr, group_type_name.c_str(), node_handle, now);
if (!recorded_args.has(obj, group_addr_, node_addr_)) {
recorded_args.insert(obj, group_addr_, node_addr_);

record(obj, group_addr, group_type_name.c_str(), now);
record(obj, group_addr, group_type_name.c_str(), node_handle, now);
}
}

bool SYMBOL_CONCAT_3(
_ZN6rclcpp9executors31StaticExecutorEntitiesCollector18add_callback_groupESt10shared_ptr,
INS_13CallbackGroupEES2_INS_15node_interfaces17NodeBaseInterface,
EERSt3mapISt8weak_ptrIS3_ES9_IS6_ESt10owner_lessISA_ESaISt4pairIKSA_SB_EEE)(

Check warning on line 509 in CARET_trace/src/hooked_trace_points.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (IKSA)
void * obj, rclcpp::CallbackGroup::SharedPtr group_ptr,
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
rclcpp::memory_strategy::MemoryStrategy::WeakCallbackGroupsToNodesMap & weak_groups_to_nodes)
Expand All @@ -508,17 +518,21 @@
static auto & context = Singleton<Context>::get_instance();
static auto & clock = context.get_clock();
static auto & data_container = context.get_data_container();
static auto record =
[](const void * obj, const void * group_addr, const char * group_type_name, int64_t init_time) {
tracepoint(
TRACEPOINT_PROVIDER, add_callback_group_static_executor, obj, group_addr, group_type_name,
init_time);
static auto record = [](
const void * obj, const void * group_addr, const char * group_type_name,
const void * node_handle, int64_t init_time) {
if (!context.get_controller().is_allowed_node(node_handle)) {
return;
}
tracepoint(
TRACEPOINT_PROVIDER, add_callback_group_static_executor, obj, group_addr, group_type_name,
init_time);

#ifdef DEBUG_OUTPUT
std::cerr << "add_callback_group_static_executor," << obj << "," << group_addr << ","
<< group_type_name << std::endl;
std::cerr << "add_callback_group_static_executor," << obj << "," << group_addr << ","
<< group_type_name << std::endl;
#endif
};
};

auto now = clock.now();
auto group_addr = static_cast<const void *>(group_ptr.get());
Expand All @@ -540,9 +554,10 @@
data_container.assign_add_callback_group_static_executor(record);
}

auto node_handle = node_ptr->get_rcl_node_handle();
data_container.store_add_callback_group_static_executor(
obj, group_addr, group_type_name.c_str(), now);
record(obj, group_addr, group_type_name.c_str(), now);
obj, group_addr, group_type_name.c_str(), node_handle, now);
record(obj, group_addr, group_type_name.c_str(), node_handle, now);

return ret;
}
Expand All @@ -558,6 +573,9 @@
static auto & clock = context.get_clock();
static auto & data_container = context.get_data_container();
static auto record = [](const void * obj, const void * timer_handle, int64_t init_time) {
if (!context.get_controller().is_allowed_timer_handle(timer_handle)) {
return;
}
tracepoint(TRACEPOINT_PROVIDER, callback_group_add_timer, obj, timer_handle, init_time);

#ifdef DEBUG_OUTPUT
Expand Down Expand Up @@ -591,6 +609,9 @@
static auto & clock = context.get_clock();
static auto & data_container = context.get_data_container();
static auto record = [](const void * obj, const void * subscription_handle, int64_t init_time) {
if (!context.get_controller().is_allowed_subscription_handle(subscription_handle)) {
return;
}
tracepoint(
TRACEPOINT_PROVIDER, callback_group_add_subscription, obj, subscription_handle, init_time);

Expand Down Expand Up @@ -627,6 +648,9 @@
static auto & clock = context.get_clock();
static auto & data_container = context.get_data_container();
static auto record = [](const void * obj, const void * service_handle, int64_t init_time) {
if (!context.get_controller().is_allowed_service_handle(service_handle)) {
return;
}
tracepoint(TRACEPOINT_PROVIDER, callback_group_add_service, obj, service_handle, init_time);

#ifdef DEBUG_OUTPUT
Expand Down Expand Up @@ -660,6 +684,9 @@
static auto & clock = context.get_clock();
static auto & data_container = context.get_data_container();
static auto record = [](const void * obj, const void * client_handle, int64_t init_time) {
if (!context.get_controller().is_allowed_client_handle(client_handle)) {
return;
}
tracepoint(TRACEPOINT_PROVIDER, callback_group_add_client, obj, client_handle, init_time);

#ifdef DEBUG_OUTPUT
Expand Down
Loading
Loading