Skip to content

Commit

Permalink
fixed
Browse files Browse the repository at this point in the history
Signed-off-by: ISP akm <[email protected]>
  • Loading branch information
xygyo77 committed Mar 7, 2024
1 parent bb9164e commit d24f44b
Show file tree
Hide file tree
Showing 4 changed files with 66 additions and 58 deletions.
18 changes: 10 additions & 8 deletions CARET_trace/src/hooked_trace_points.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,17 +189,19 @@ void update_dds_function_addr()
"Could not load library %s: %s", library_name.c_str(), e.what());
}

static auto record = [](const char * rmw_implementation, int64_t init_time) {
tracepoint(TRACEPOINT_PROVIDER, rmw_implementation, rmw_implementation, init_time);
};
if (context.get_controller().is_allowed_process()) {
static auto record = [](const char * rmw_implementation, int64_t init_time) {
tracepoint(TRACEPOINT_PROVIDER, rmw_implementation, rmw_implementation, init_time);
};

if (!data_container.is_assigned_rmw_implementation()) {
data_container.assign_rmw_implementation(record);
}
if (!data_container.is_assigned_rmw_implementation()) {
data_container.assign_rmw_implementation(record);
}

data_container.store_rmw_implementation(env_var.c_str(), now);
data_container.store_rmw_implementation(env_var.c_str(), now);

record(env_var.c_str(), now);
record(env_var.c_str(), now);
}

if (env_var == "rmw_fastrtps_cpp") {
// clang-format off
Expand Down
94 changes: 47 additions & 47 deletions CARET_trace/src/ros_trace_points.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -244,10 +244,6 @@ void ros_trace_rcl_node_init(
static auto & context = Singleton<Context>::get_instance();
static auto & controller = context.get_controller();

if (!controller.is_allowed_process()) {
return;
}

if (!controller.is_allowed_node(node_handle)) {
return;
}
Expand All @@ -262,6 +258,10 @@ void ros_trace_rcl_node_init(
#endif
};

if (!controller.is_allowed_process()) {
return;
}

auto now = clock.now();

check_and_run_trace_node();
Expand Down Expand Up @@ -307,10 +307,6 @@ void ros_trace_rcl_subscription_init(
static auto & context = Singleton<Context>::get_instance();
static auto & controller = context.get_controller();

if (!controller.is_allowed_process()) {
return;
}

if (!controller.is_allowed_subscription_handle(subscription_handle)) {
return;
}
Expand All @@ -326,6 +322,10 @@ void ros_trace_rcl_subscription_init(
#endif
};

if (!controller.is_allowed_process()) {
return;
}

auto now = clock.now();

controller.add_subscription_handle(node_handle, subscription_handle, topic_name);
Expand Down Expand Up @@ -359,11 +359,6 @@ void ros_trace_rclcpp_subscription_init(
) {
static auto & context = Singleton<Context>::get_instance();
static auto & controller = context.get_controller();

if (!controller.is_allowed_process()) {
return;
}

if (!controller.is_allowed_subscription_handle(subscription_handle)){
return;
}
Expand All @@ -376,6 +371,10 @@ void ros_trace_rclcpp_subscription_init(
#endif
};

if (!controller.is_allowed_process()) {
return;
}

auto now = clock.now();
check_and_run_trace_node();

Expand Down Expand Up @@ -404,11 +403,6 @@ void ros_trace_rclcpp_subscription_callback_added(
const void * callback,
int64_t init_time
) {

if (!controller.is_allowed_process()) {
return;
}

if (!controller.is_allowed_callback(callback)) {
return;
}
Expand All @@ -421,6 +415,10 @@ void ros_trace_rclcpp_subscription_callback_added(
#endif
};

if (!controller.is_allowed_process()) {
return;
}

auto now = clock.now();
check_and_run_trace_node();

Expand All @@ -447,11 +445,6 @@ void ros_trace_rclcpp_timer_callback_added(const void * timer_handle, const void
const void * callback,
int64_t init_time
) {

if (!controller.is_allowed_process()) {
return;
}

if (!controller.is_allowed_callback(callback)) {
return;
}
Expand All @@ -463,6 +456,10 @@ void ros_trace_rclcpp_timer_callback_added(const void * timer_handle, const void
#endif
};

if (!controller.is_allowed_process()) {
return;
}

auto now = clock.now();
check_and_run_trace_node();

Expand All @@ -487,11 +484,6 @@ void ros_trace_rclcpp_timer_link_node(const void * timer_handle, const void * no
const void * node_handle,
int64_t init_time
) {

if (!controller.is_allowed_process()) {
return;
}

if (!controller.is_allowed_node(node_handle)) {
return;
}
Expand All @@ -503,6 +495,10 @@ void ros_trace_rclcpp_timer_link_node(const void * timer_handle, const void * no
#endif
};

if (!controller.is_allowed_process()) {
return;
}

auto now = clock.now();
check_and_run_trace_node();

Expand Down Expand Up @@ -724,12 +720,11 @@ void ros_trace_rcl_init(
tracepoint(TRACEPOINT_PROVIDER, rcl_init, context_handle, init_time);
};

auto now = clock.now();

if (!context.get_controller().is_allowed_process()) {
return;
}

auto now = clock.now();
if (!data_container.is_assigned_rcl_init()) {
data_container.assign_rcl_init(record);
}
Expand Down Expand Up @@ -767,16 +762,16 @@ void ros_trace_rcl_publisher_init(
rmw_publisher_handle, topic_name, queue_depth, init_time);
};

if (!controller.is_allowed_process()) {
return;
}

auto now = clock.now();
controller.add_publisher_handle(node_handle, publisher_handle, topic_name);

// TODO(hsgwa): support topic_name filtering
// It seems to be executed before the topic name and node name are known.

if (!controller.is_allowed_process()) {
return;
}

if (!data_container.is_assigned_rcl_publisher_init()) {
data_container.assign_rcl_publisher_init(record);
}
Expand Down Expand Up @@ -855,12 +850,12 @@ void ros_trace_rcl_service_init(
#endif
};

auto now = clock.now();

if (!context.get_controller().is_allowed_process()) {
return;
}

auto now = clock.now();

if (!data_container.is_assigned_rcl_service_init()) {
data_container.assign_rcl_service_init(record);
}
Expand Down Expand Up @@ -889,12 +884,13 @@ void ros_trace_rclcpp_service_callback_added(
callback << std::endl;
#endif
};
auto now = clock.now();

if (!context.get_controller().is_allowed_process()) {
return;
}

auto now = clock.now();

check_and_run_trace_node();

if (!data_container.is_assigned_rclcpp_service_callback_added()) {
Expand Down Expand Up @@ -930,12 +926,13 @@ void ros_trace_rcl_client_init(
service_name << std::endl;
#endif
};
auto now = clock.now();

if (!context.get_controller().is_allowed_process()) {
return;
}

auto now = clock.now();

if (!data_container.is_assigned_rcl_client_init()) {
data_container.assign_rcl_client_init(record);
}
Expand Down Expand Up @@ -974,12 +971,13 @@ void ros_trace_rclcpp_callback_register(
symbol << std::endl;
#endif
};
auto now = clock.now();

if (!context.get_controller().is_allowed_process()) {
return;
}

auto now = clock.now();

check_and_run_trace_node();

if (!data_container.is_assigned_rclcpp_callback_register()) {
Expand Down Expand Up @@ -1024,12 +1022,13 @@ void ros_trace_do_rclcpp_callback_register(
symbol << std::endl;
#endif
};
auto now = clock.now();

if (!context.get_controller().is_allowed_process()) {
return;
}

auto now = clock.now();

check_and_run_trace_node();

if (!data_container.is_assigned_rclcpp_callback_register()) {
Expand Down Expand Up @@ -1060,12 +1059,13 @@ void ros_trace_rcl_lifecycle_state_machine_init(
state_machine << std::endl;
#endif
};
auto now = clock.now();

if (!context.get_controller().is_allowed_process()) {
return;
}

auto now = clock.now();

check_and_run_trace_node();

record(node_handle, state_machine, now);
Expand Down Expand Up @@ -1269,12 +1269,12 @@ void ros_trace_rclcpp_buffer_to_ipb(
#endif
};

auto now = clock.now();

if (!controller.is_allowed_process()) {
return;
}

auto now = clock.now();

if (!data_container.is_assigned_rclcpp_buffer_to_ipb()){
data_container.assign_rclcpp_buffer_to_ipb(record);
}
Expand Down Expand Up @@ -1311,12 +1311,12 @@ void ros_trace_rclcpp_ipb_to_subscription(
#endif
};

auto now = clock.now();

if (!controller.is_allowed_process()) {
return;
}

auto now = clock.now();

if (!data_container.is_assigned_rclcpp_ipb_to_subscription()){
data_container.assign_rclcpp_ipb_to_subscription(record);
}
Expand Down Expand Up @@ -1350,12 +1350,12 @@ void ros_trace_rclcpp_construct_ring_buffer(
#endif
};

auto now = clock.now();

if (!context.get_controller().is_allowed_process()) {
return;
}

auto now = clock.now();

if (!data_container.is_assigned_rclcpp_construct_ring_buffer()) {
data_container.assign_rclcpp_construct_ring_buffer(record);
}
Expand Down
4 changes: 4 additions & 0 deletions CARET_trace/src/trace_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,10 @@ void TraceNode::start_callback(caret_msgs::msg::Start::UniquePtr msg)

debug("Received start message.");

if (!context.get_controller().is_allowed_process()) {
return;
}

// As long as PREPARE state, data of initialization trace point are stored into pending.
// Before calling the caret_init trace point,
// transition to the prepare state to set is_recording_allowed to False.
Expand Down
8 changes: 5 additions & 3 deletions CARET_trace/src/tracing_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -441,13 +441,15 @@ bool TracingController::is_allowed_buffer(const void * buffer)
bool TracingController::is_allowed_process()
{
if (ignore_enabled_) {
auto is_ignored_process = partial_match(ignored_process_names_, std::string(program_invocation_short_name));
auto is_ignored_process = partial_match(
ignored_process_names_,
std::string(program_invocation_short_name)
);
if (is_ignored_process && ignored_process_names_.size() > 0) {
RCLCPP_DEBUG(rclcpp::get_logger("caret"), program_invocation_short_name);
return false;
}
return true;
}
return true;
}

std::string TracingController::to_node_name(const void * callback)
Expand Down

0 comments on commit d24f44b

Please sign in to comment.