Skip to content

Commit

Permalink
Add tracing instrumentation for executor and message taking
Browse files Browse the repository at this point in the history
Signed-off-by: Christophe Bedard <bedard.christophe@gmail.com>
  • Loading branch information
christophebedard committed Aug 2, 2021
1 parent d5f3d35 commit d719b43
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 0 deletions.
10 changes: 10 additions & 0 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@

#include "rcutils/logging_macros.h"

#include "tracetools/tracetools.h"

using namespace std::chrono_literals;

using rclcpp::exceptions::throw_from_rcl_error;
Expand Down Expand Up @@ -515,9 +517,15 @@ Executor::execute_any_executable(AnyExecutable & any_exec)
return;
}
if (any_exec.timer) {
TRACEPOINT(
rclcpp_executor_execute,
static_cast<const void *>(any_exec.timer->get_timer_handle().get()));
execute_timer(any_exec.timer);
}
if (any_exec.subscription) {
TRACEPOINT(
rclcpp_executor_execute,
static_cast<const void *>(any_exec.subscription->get_subscription_handle().get()));
execute_subscription(any_exec.subscription);
}
if (any_exec.service) {
Expand Down Expand Up @@ -678,6 +686,7 @@ Executor::execute_client(
void
Executor::wait_for_work(std::chrono::nanoseconds timeout)
{
TRACEPOINT(rclcpp_executor_wait_for_work, timeout.count());
{
std::lock_guard<std::mutex> guard(mutex_);

Expand Down Expand Up @@ -827,6 +836,7 @@ Executor::get_next_ready_executable_from_map(
const rclcpp::memory_strategy::MemoryStrategy::WeakCallbackGroupsToNodesMap &
weak_groups_to_nodes)
{
TRACEPOINT(rclcpp_executor_get_next_ready);
bool success = false;
std::lock_guard<std::mutex> guard{mutex_};
// Check the timers to see if there are any that are ready
Expand Down
1 change: 1 addition & 0 deletions rclcpp/src/rclcpp/subscription_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,7 @@ SubscriptionBase::take_type_erased(void * message_out, rclcpp::MessageInfo & mes
&message_info_out.get_rmw_message_info(),
nullptr // rmw_subscription_allocation_t is unused here
);
TRACEPOINT(rclcpp_take, static_cast<const void *>(message_out));
if (RCL_RET_SUBSCRIPTION_TAKE_FAILED == ret) {
return false;
} else if (RCL_RET_OK != ret) {
Expand Down

0 comments on commit d719b43

Please sign in to comment.