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

Support jump handlers with only pre- or post-jump callback #517

Merged
merged 3 commits into from
Jul 17, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
8 changes: 6 additions & 2 deletions rclcpp/src/rclcpp/clock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,9 @@ Clock::invoke_prejump_callbacks(
const std::vector<JumpHandler::SharedPtr> & callbacks)
{
for (const auto cb : callbacks) {
cb->pre_callback();
if (cb->pre_callback != nullptr) {
cb->pre_callback();
}
}
}

Expand All @@ -163,7 +165,9 @@ Clock::invoke_postjump_callbacks(
const TimeJump & jump)
{
for (auto cb : callbacks) {
cb->post_callback(jump);
if (cb->post_callback != nullptr) {
cb->post_callback(jump);
}
}
}

Expand Down
104 changes: 44 additions & 60 deletions rclcpp/test/test_time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,29 @@ class TestTimeSource : public ::testing::Test
rclcpp::Node::SharedPtr node;
};

void trigger_clock_changes(
rclcpp::Node::SharedPtr node)
{
auto clock_pub = node->create_publisher<rosgraph_msgs::msg::Clock>("clock",
rmw_qos_profile_default);

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);

rclcpp::WallRate loop_rate(50);
for (int i = 0; i < 5; ++i) {
if (!rclcpp::ok()) {
break; // Break for ctrl-c
}
auto msg = std::make_shared<rosgraph_msgs::msg::Clock>();
msg->clock.sec = i;
msg->clock.nanosec = 1000;
clock_pub->publish(msg);
executor.spin_once(1000000ns);
loop_rate.sleep();
}
}

TEST_F(TestTimeSource, detachUnattached) {
rclcpp::TimeSource ts;

Expand Down Expand Up @@ -92,20 +115,8 @@ TEST_F(TestTimeSource, clock) {
ts.attachClock(ros_clock);
EXPECT_FALSE(ros_clock->ros_time_is_active());

auto clock_pub = node->create_publisher<rosgraph_msgs::msg::Clock>("clock",
rmw_qos_profile_default);
rclcpp::WallRate loop_rate(50);
for (int i = 0; i < 5; ++i) {
if (!rclcpp::ok()) {
break; // Break for ctrl-c
}
auto msg = std::make_shared<rosgraph_msgs::msg::Clock>();
msg->clock.sec = i;
msg->clock.nanosec = 1000;
clock_pub->publish(msg);
rclcpp::spin_some(node);
loop_rate.sleep();
}
trigger_clock_changes(node);

auto t_low = rclcpp::Time(1, 0, RCL_ROS_TIME);
auto t_high = rclcpp::Time(10, 100000, RCL_ROS_TIME);

Expand Down Expand Up @@ -161,21 +172,7 @@ TEST_F(TestTimeSource, callbacks) {
ts.attachClock(ros_clock);
EXPECT_FALSE(ros_clock->ros_time_is_active());

auto clock_pub = node->create_publisher<rosgraph_msgs::msg::Clock>("clock",
rmw_qos_profile_default);

rclcpp::WallRate loop_rate(50);
for (int i = 0; i < 5; ++i) {
if (!rclcpp::ok()) {
break; // Break for ctrl-c
}
auto msg = std::make_shared<rosgraph_msgs::msg::Clock>();
msg->clock.sec = i;
msg->clock.nanosec = 1000;
clock_pub->publish(msg);
rclcpp::spin_some(node);
loop_rate.sleep();
}
trigger_clock_changes(node);
auto t_low = rclcpp::Time(1, 0, RCL_ROS_TIME);
auto t_high = rclcpp::Time(10, 100000, RCL_ROS_TIME);

Expand All @@ -198,17 +195,7 @@ TEST_F(TestTimeSource, callbacks) {
std::bind(&CallbackObject::post_callback, &cbo, std::placeholders::_1, 2),
jump_threshold);

for (int i = 0; i < 5; ++i) {
if (!rclcpp::ok()) {
break; // Break for ctrl-c
}
auto msg = std::make_shared<rosgraph_msgs::msg::Clock>();
msg->clock.sec = i;
msg->clock.nanosec = 2000;
clock_pub->publish(msg);
rclcpp::spin_some(node);
loop_rate.sleep();
}
trigger_clock_changes(node);

EXPECT_EQ(2, cbo.last_precallback_id_);
EXPECT_EQ(2, cbo.last_postcallback_id_);
Expand All @@ -221,29 +208,26 @@ TEST_F(TestTimeSource, callbacks) {
EXPECT_NE(0L, t_out.nanoseconds());
EXPECT_LT(t_low.nanoseconds(), t_out.nanoseconds());
EXPECT_GT(t_high.nanoseconds(), t_out.nanoseconds());
}

void trigger_clock_changes(
rclcpp::Node::SharedPtr node)
{
auto clock_pub = node->create_publisher<rosgraph_msgs::msg::Clock>("clock",
rmw_qos_profile_default);
// Register a callback handler with only pre_callback
rclcpp::JumpHandler::SharedPtr callback_handler3 = ros_clock->create_jump_callback(
std::bind(&CallbackObject::pre_callback, &cbo, 3),
std::function<void(rclcpp::TimeJump)>(),
jump_threshold);

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
trigger_clock_changes(node);
EXPECT_EQ(3, cbo.last_precallback_id_);
EXPECT_EQ(2, cbo.last_postcallback_id_);

rclcpp::WallRate loop_rate(50);
for (int i = 0; i < 5; ++i) {
if (!rclcpp::ok()) {
break; // Break for ctrl-c
}
auto msg = std::make_shared<rosgraph_msgs::msg::Clock>();
msg->clock.sec = i;
msg->clock.nanosec = 1000;
clock_pub->publish(msg);
executor.spin_once(1000000ns);
loop_rate.sleep();
}
// Register a callback handler with only post_callback
rclcpp::JumpHandler::SharedPtr callback_handler4 = ros_clock->create_jump_callback(
std::function<void()>(),
std::bind(&CallbackObject::post_callback, &cbo, std::placeholders::_1, 4),
jump_threshold);

trigger_clock_changes(node);
EXPECT_EQ(3, cbo.last_precallback_id_);
EXPECT_EQ(4, cbo.last_postcallback_id_);
}


Expand Down