Skip to content

Commit

Permalink
fix test_static_publisher in macos (#284)
Browse files Browse the repository at this point in the history
* Attempt to fix test_static_publisher in macos

Signed-off-by: ahcorde <ahcorde@gmail.com>

* make linters happy

Signed-off-by: ahcorde <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Jul 1, 2020
1 parent 0395030 commit e40c27d
Showing 1 changed file with 36 additions and 4 deletions.
40 changes: 36 additions & 4 deletions test_tf2/test/test_static_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@

#include "permuter.hpp"

const int MAX_ATTEMPTS = 100;

TEST(StaticTransformPublisher, a_b_different_times)
{
auto node = rclcpp::Node::make_shared("StaticTransformPublisher_a_b_different_times_test");
Expand All @@ -60,7 +62,15 @@ TEST(StaticTransformPublisher, a_b_different_times)
std::thread spin_thread = std::thread(
std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor));

std::this_thread::sleep_for(std::chrono::milliseconds(200));
int attempts = 0;

while (!mB.canTransform("a", "b", tf2::timeFromSec(0))) {
std::this_thread::sleep_for(std::chrono::milliseconds(50));
attempts++;
if (attempts > MAX_ATTEMPTS) {
FAIL();
}
}

EXPECT_TRUE(mB.canTransform("a", "b", tf2::timeFromSec(0)));
EXPECT_TRUE(mB.canTransform("a", "b", tf2::timeFromSec(100)));
Expand All @@ -85,7 +95,14 @@ TEST(StaticTransformPublisher, a_c_different_times)
std::thread spin_thread = std::thread(
std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor));

std::this_thread::sleep_for(std::chrono::milliseconds(200));
int attempts = 0;
while (!mB.canTransform("a", "c", tf2::timeFromSec(0))) {
std::this_thread::sleep_for(std::chrono::milliseconds(50));
attempts++;
if (attempts > MAX_ATTEMPTS) {
FAIL();
}
}

EXPECT_TRUE(mB.canTransform("a", "c", tf2::timeFromSec(0)));
EXPECT_TRUE(mB.canTransform("a", "c", tf2::timeFromSec(10)));
Expand All @@ -110,7 +127,15 @@ TEST(StaticTransformPublisher, a_d_different_times)
std::thread spin_thread = std::thread(
std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor));

std::this_thread::sleep_for(std::chrono::milliseconds(200));
int attempts = 0;

while (!mB.canTransform("a", "c", tf2::timeFromSec(0))) {
std::this_thread::sleep_for(std::chrono::milliseconds(50));
attempts++;
if (attempts > MAX_ATTEMPTS) {
FAIL();
}
}

geometry_msgs::msg::TransformStamped ts;
ts.transform.rotation.w = 1;
Expand Down Expand Up @@ -151,8 +176,15 @@ TEST(StaticTransformPublisher, multiple_parent_test)
std::thread spin_thread = std::thread(
std::bind(&rclcpp::executors::SingleThreadedExecutor::spin, &executor));

std::this_thread::sleep_for(std::chrono::milliseconds(200));
int attempts = 0;

while (!mB.canTransform("a", "b", tf2::timeFromSec(0))) {
std::this_thread::sleep_for(std::chrono::milliseconds(50));
attempts++;
if (attempts > MAX_ATTEMPTS) {
FAIL();
}
}

tf2_ros::StaticTransformBroadcaster stb(node);
geometry_msgs::msg::TransformStamped ts;
Expand Down

0 comments on commit e40c27d

Please sign in to comment.