Skip to content

Commit

Permalink
Allow node clock use in logging macros (#969) (#970)
Browse files Browse the repository at this point in the history
Capturing a cached reference allows a clock object that is not a local
(e.g. the one returned by Node::get_clock()) to be passed to the throttle
logging macro.

Signed-off-by: Matt Schickler <mschickler@gmail.com>
Co-Authored-By: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
  • Loading branch information
mschickler and ivanpauno committed Jan 28, 2020
1 parent fdaf96f commit 3ec882c
Show file tree
Hide file tree
Showing 2 changed files with 40 additions and 3 deletions.
4 changes: 2 additions & 2 deletions rclcpp/resource/logging.hpp.em
Original file line number Diff line number Diff line change
Expand Up @@ -129,9 +129,9 @@ def get_rclcpp_suffix_from_features(features):
typename ::rclcpp::Logger>::value, \
"First argument to logging macros must be an rclcpp::Logger"); \
@[ if 'throttle' in feature_combination]@ \
auto get_time_point = [&clock](rcutils_time_point_value_t * time_point) -> rcutils_ret_t { \
auto get_time_point = [&c=clock](rcutils_time_point_value_t * time_point) -> rcutils_ret_t { \
try { \
*time_point = clock.now().nanoseconds(); \
*time_point = c.now().nanoseconds(); \
} catch (...) { \
RCUTILS_SAFE_FWRITE_TO_STDERR( \
"[rclcpp|logging.hpp] RCLCPP_@(severity)@(suffix) could not get current time stamp\n"); \
Expand Down
39 changes: 38 additions & 1 deletion rclcpp/test/test_logging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,16 +77,33 @@ class TestLoggingMacros : public ::testing::Test
}
};

class DummyNode
{
public:
DummyNode()
{
clock_ = rclcpp::Clock::make_shared(RCL_ROS_TIME);
}
rclcpp::Clock::SharedPtr get_clock()
{
return clock_;
}

private:
rclcpp::Clock::SharedPtr clock_;
};

TEST_F(TestLoggingMacros, test_logging_named) {
for (int i : {1, 2, 3}) {
RCLCPP_DEBUG(g_logger, "message %d", i);
}
size_t expected_location = __LINE__ - 2u;
EXPECT_EQ(3u, g_log_calls);
EXPECT_TRUE(g_last_log_event.location != NULL);
if (g_last_log_event.location) {
EXPECT_STREQ("TestBody", g_last_log_event.location->function_name);
EXPECT_THAT(g_last_log_event.location->file_name, EndsWith("test_logging.cpp"));
EXPECT_EQ(82u, g_last_log_event.location->line_number);
EXPECT_EQ(expected_location, g_last_log_event.location->line_number);
}
EXPECT_EQ(RCUTILS_LOG_SEVERITY_DEBUG, g_last_log_event.level);
EXPECT_EQ("name", g_last_log_event.name);
Expand Down Expand Up @@ -210,6 +227,26 @@ TEST_F(TestLoggingMacros, test_throttle) {
EXPECT_EQ(6u, g_log_calls);
}
}
DummyNode node;
rcl_clock_t * node_clock = node.get_clock()->get_clock_handle();
ASSERT_TRUE(node_clock);
ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(node_clock));
EXPECT_EQ(6u, g_log_calls);
EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(node_clock, RCUTILS_MS_TO_NS(10)));
for (uint64_t i = 0; i < 3; ++i) {
RCLCPP_DEBUG_THROTTLE(g_logger, *node.get_clock(), 10, "Throttling");
if (i == 0) {
EXPECT_EQ(7u, g_log_calls);
rcl_time_point_value_t clock_ns = node.get_clock()->now().nanoseconds() + RCUTILS_MS_TO_NS(5);
EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(node_clock, clock_ns));
} else if (i == 1) {
EXPECT_EQ(7u, g_log_calls);
rcl_time_point_value_t clock_ns = node.get_clock()->now().nanoseconds() + RCUTILS_MS_TO_NS(5);
EXPECT_EQ(RCL_RET_OK, rcl_set_ros_time_override(node_clock, clock_ns));
} else {
EXPECT_EQ(8u, g_log_calls);
}
}
}

bool log_function(rclcpp::Logger logger)
Expand Down

0 comments on commit 3ec882c

Please sign in to comment.