Spin before checking if clock changed (#483)

This commit is contained in:
Shane Loretz 2018-05-30 15:09:30 -07:00 committed by GitHub
parent d82ce9666c
commit 4efcd330fe
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23

View file

@ -50,7 +50,6 @@ protected:
rclcpp::Node::SharedPtr node;
};
TEST_F(TestTimeSource, detachUnattached) {
rclcpp::TimeSource ts;
@ -344,16 +343,19 @@ TEST_F(TestTimeSource, parameter_activation) {
for (auto & result : set_parameters_results) {
EXPECT_TRUE(result.successful);
}
// SyncParametersClient returns when parameters have been set on the node_parameters interface,
// but it doesn't mean the on_parameter_event subscription in TimeSource has been called.
// Spin some to handle that subscription.
rclcpp::spin_some(node);
EXPECT_TRUE(ros_clock->ros_time_is_active());
set_parameters_results = parameters_client->set_parameters({
rclcpp::parameter::ParameterVariant("use_sim_time", rclcpp::parameter::PARAMETER_NOT_SET)
});
for (auto & result : set_parameters_results) {
EXPECT_TRUE(result.successful);
}
rclcpp::spin_some(node);
EXPECT_TRUE(ros_clock->ros_time_is_active());
set_parameters_results = parameters_client->set_parameters({
@ -362,6 +364,7 @@ TEST_F(TestTimeSource, parameter_activation) {
for (auto & result : set_parameters_results) {
EXPECT_TRUE(result.successful);
}
rclcpp::spin_some(node);
EXPECT_FALSE(ros_clock->ros_time_is_active());
set_parameters_results = parameters_client->set_parameters({
@ -370,5 +373,6 @@ TEST_F(TestTimeSource, parameter_activation) {
for (auto & result : set_parameters_results) {
EXPECT_TRUE(result.successful);
}
rclcpp::spin_some(node);
EXPECT_FALSE(ros_clock->ros_time_is_active());
}