Skip to content

Commit

Permalink
fix: node filter improvement (#280)
Browse files Browse the repository at this point in the history
* add environment variable CARET_IGNORE_PROCESSES.

Signed-off-by: ISP akm <[email protected]>

* add CARET_IGNORE_PROCESSES environment variable

Signed-off-by: ISP akm <[email protected]>

* fixed

Signed-off-by: ISP akm <[email protected]>

* ci(pre-commit): autofix

* PR Review Reflection

Signed-off-by: ISP akm <[email protected]>

* ci(pre-commit): autofix

* Changed usage of std::unoderd_map in tracing_controller.cpp.

Signed-off-by: ISP akm <[email protected]>

* The node_ptr of the function rclcpp::Executor::add_callback_group_to_map() should be of type rclcpp::node_interfaces::NodeBaseInterface::SharedPtr and the argument of orig_func() should also be The argument of orig_func() should be the same type.

Signed-off-by: ISP akm <[email protected]>

* for debugging version

Signed-off-by: ISP akm <[email protected]>

* insert debugging code

Signed-off-by: ISP akm <[email protected]>

* under review

Signed-off-by: ISP akm <[email protected]>

* fixed

Signed-off-by: ISP akm <[email protected]>

* add cache clear

Signed-off-by: ISP akm <[email protected]>

* allowed_callbacks_ maintenance

Signed-off-by: ISP akm <[email protected]>

* fixed

Signed-off-by: ISP akm <[email protected]>

* add debug code

Signed-off-by: ISP akm <[email protected]>

* modify debug code

Signed-off-by: ISP akm <[email protected]>

* modify debug code

Signed-off-by: ISP akm <[email protected]>

* fixed review results

Signed-off-by: ISP akm <[email protected]>

* fixed

Signed-off-by: ISP akm <[email protected]>

* fixed

Signed-off-by: ISP akm <[email protected]>

* fixed

Signed-off-by: ISP akm <[email protected]>

* add subscription_to_subscription_handles_

Signed-off-by: ISP akm <[email protected]>

* add message_construct filter

Signed-off-by: ISP akm <[email protected]>

* fixed

Signed-off-by: ISP akm <[email protected]>

* remove debug codes

Signed-off-by: ISP akm <[email protected]>

* ci(pre-commit): autofix

* Fixed omission of experimental code deletion.

Signed-off-by: ISP akm <[email protected]>

* ci(pre-commit): autofix

* spelling correction

Signed-off-by: ISP akm <[email protected]>

* Update CARET_trace/src/ros_trace_points.cpp

Co-authored-by: ymski <[email protected]>

* Update CARET_trace/include/caret_trace/tracing_controller.hpp

Co-authored-by: ymski <[email protected]>

* remove debug code

Signed-off-by: ISP akm <[email protected]>

* Update CARET_trace/include/caret_trace/tracing_controller.hpp

Co-authored-by: ymski <[email protected]>

* Delete unnecessary codes.

Signed-off-by: ISP akm <[email protected]>

* Correction by review.

Signed-off-by: ISP akm <[email protected]>

* Correction by review.

Signed-off-by: ISP akm <[email protected]>

* Suppress /rosout output after /iron.

Signed-off-by: ISP akm <[email protected]>

* ci(pre-commit): autofix

* Update CARET_trace/include/caret_trace/data_container.hpp

Co-authored-by: ymski <[email protected]>

* fixed debug message

Signed-off-by: ISP akm <[email protected]>

* improve message construct

Signed-off-by: ISP akm <[email protected]>

* modify is_allowed_message()

Signed-off-by: ISP akm <[email protected]>

* ci(pre-commit): autofix

* Update CARET_trace/include/caret_trace/tracing_controller.hpp

Co-authored-by: ymski <[email protected]>

---------

Signed-off-by: ISP akm <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: ymski <[email protected]>
  • Loading branch information
3 people authored Apr 25, 2024
1 parent a89d99a commit 27302e7
Show file tree
Hide file tree
Showing 5 changed files with 669 additions and 119 deletions.
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 @@ class DataContainerInterface
/// @return True if record has finished, false otherwise.
virtual bool record(uint64_t loop_count = 1) = 0;

/// @brief transitionto recording state.
/// @brief transition to recording state.
virtual void start_recording() = 0;

/// @brief Reset recording state.
Expand All @@ -48,11 +48,12 @@ class DataContainer : public DataContainerInterface
{
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
88 changes: 79 additions & 9 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 Down Expand Up @@ -53,19 +53,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);
/// @param subscription Address of subscription instance.
void add_subscription_callback(const void * callback, const void * subscription);

/// @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 @@ -75,9 +75,9 @@ class TracingController
const void * node_handle, const void * publisher_handle, std::string topic_name);

/// @brief Register binding information for rclcpp_timer_callback_added tracepoint hook.
/// @param callback Address of timer callback instance.
/// @param timer_handle Address of the timer handle.
/// @param callback Address of callback instance.
void add_timer_callback(const void * timer_handle, const void * callback);
void add_timer_callback(const void * timer_callback, const void * timer_handle);

/// @brief Register binding information for rclcpp_buffer_to_ipb tracepoint.
/// @param buffer Address of the buffer.
Expand All @@ -89,6 +89,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.
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.
void add_client_handle(const void * client_handle, const void * node_handle);

/// @brief Registering acceptable and unacceptable message.
/// @param message Address of the intra original message.
/// @param is_allowed True is enabled, false otherwise.
void add_allowed_messages(const void * message, bool is_allowed);

/// @brief Check if trace point is a enabled callback
/// @param callback
/// @param callback Address of callback instance.
Expand All @@ -105,6 +125,13 @@ class TracingController
/// @return True if the publisher is enabled, false otherwise.
bool is_allowed_publisher_handle(const void * publisher_handle);

/// @brief Check if trace point is a enabled publisher and set to allowed message map
/// @param publisher_handle Address of the publisher handle.
/// @param message Address of the message.
/// @return True if the publisher is enabled, false otherwise.
bool is_allowed_publisher_handle_and_add_message(
const void * publisher_handle, const void * message);

/// @brief Check if trace point is a enabled subscription
/// @param subscription_handle Address of the subscription handle.
/// @return True if the subscription is enabled, false otherwise.
Expand All @@ -124,6 +151,36 @@ class TracingController
/// @return True if the process is enabled, false otherwise.
bool is_allowed_process();

/// @brief Check if trace point is a enabled timer handle
/// @param timer_handle Address of the timer handle.
/// @return True if the timer_handle is enabled, false otherwise.
bool is_allowed_timer_handle(const void * timer_handle);

/// @brief Check if trace point is a enabled state machine
/// @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 ipb
/// @param buffer Address of the intra-process buffer.
/// @return True if the ipb is enabled, false otherwise.
bool is_allowed_ipb(const void * ipb);

/// @brief Check if trace point is a enabled service handle
/// @param service_handle Address of the service handle.
/// @return True if the service_handle is enabled, false otherwise.
bool is_allowed_service_handle(const void * service_handle);

/// @brief Check if trace point is a enabled client handle
/// @param client_handle Address of the client handle.
/// @return True if the client_handle is enabled, false otherwise.
bool is_allowed_client_handle(const void * client_handle);

/// @brief Check if trace point is a enabled publisher
/// @param message Address of the message.
/// @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 +206,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 +216,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 +225,17 @@ 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_handles_;
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 *, bool> allowed_messages_;
};

#endif // CARET_TRACE__TRACING_CONTROLLER_HPP_
Expand Down
88 changes: 57 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,12 @@ int dds_writecdr_impl(void * wr, void * xp, struct ddsi_serdata * dinp, bool flu
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," << serialized_message_addr << "," << dinp->timestamp.v
<< std::endl;
#endif
}
return dds_return;
Expand All @@ -278,7 +279,6 @@ void _ZN8eprosima8fastrtps4rtps13WriterHistory13set_fragmentsEPNS1_13CacheChange
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 +289,7 @@ void _ZN8eprosima8fastrtps4rtps13WriterHistory13set_fragmentsEPNS1_13CacheChange
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 Down Expand Up @@ -421,7 +421,7 @@ void _ZN6rclcpp9executors28StaticSingleThreadedExecutorC1ERKNS_15ExecutorOptions
}

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 +439,35 @@ void SYMBOL_CONCAT_3(
_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 +481,8 @@ void SYMBOL_CONCAT_3(

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,11 +492,13 @@ void SYMBOL_CONCAT_3(
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);
}
}

Expand All @@ -508,17 +517,21 @@ bool SYMBOL_CONCAT_3(
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 +553,10 @@ bool SYMBOL_CONCAT_3(
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 +572,9 @@ void _ZN6rclcpp13CallbackGroup9add_timerESt10shared_ptrINS_9TimerBaseEE(
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 +608,9 @@ void _ZN6rclcpp13CallbackGroup16add_subscriptionESt10shared_ptrINS_16Subscriptio
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 +647,9 @@ void _ZN6rclcpp13CallbackGroup11add_serviceESt10shared_ptrINS_11ServiceBaseEE(
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 +683,9 @@ void _ZN6rclcpp13CallbackGroup10add_clientESt10shared_ptrINS_10ClientBaseEE(
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

0 comments on commit 27302e7

Please sign in to comment.