Skip to content

Commit

Permalink
Improve test stability (#363)
Browse files Browse the repository at this point in the history
Wait until mcl_3dl node init.
  • Loading branch information
at-wat authored Dec 13, 2020
1 parent 9acc67d commit c170897
Show file tree
Hide file tree
Showing 4 changed files with 40 additions and 0 deletions.
10 changes: 10 additions & 0 deletions test/src/test_beam_label.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -175,6 +175,16 @@ class BeamLabel : public ::testing::Test
void SetUp()
{
pub_init_.publish(generateInitialPose());
ros::Rate wait(10);
for (int i = 0; i < 100; i++)
{
wait.sleep();
ros::spinOnce();
if (pose_cov_)
break;
if (!ros::ok())
break;
}
}

public:
Expand Down
10 changes: 10 additions & 0 deletions test/src/test_expansion_resetting.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,6 +213,16 @@ class ExpansionResetting : public ::testing::Test
ASSERT_TRUE(src_expansion_resetting_.waitForExistence(ros::Duration(10)));

pub_init_.publish(generateInitialPose());
ros::Rate wait(10);
for (int i = 0; i < 100; i++)
{
wait.sleep();
ros::spinOnce();
if (pose_cov_)
break;
if (!ros::ok())
break;
}
}

public:
Expand Down
9 changes: 9 additions & 0 deletions test/src/test_global_localization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,6 +206,15 @@ TEST_P(GlobalLocalization, Localize)
ros::Publisher pub_odom = nh.advertise<nav_msgs::Odometry>("odom", 1);

pub_mapcloud.publish(generateMapMsg());
ros::Rate wait(10);
for (int i = 0; i < 100; i++)
{
wait.sleep();
ros::spinOnce();
if (poses)
break;
ASSERT_TRUE(ros::ok());
}

for (float offset_x = -0.5; offset_x <= 0.51; offset_x += 1.0)
{
Expand Down
11 changes: 11 additions & 0 deletions test/src/test_landmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,7 @@ std::pair<float, float> getMean(const std::vector<geometry_msgs::Pose>& poses)
return std::pair<float, float>(mean, root_mean);
}
} // namespace

TEST(Landmark, Measurement)
{
geometry_msgs::PoseArray::ConstPtr poses;
Expand All @@ -94,6 +95,16 @@ TEST(Landmark, Measurement)

ros::Duration(1.0).sleep();
pub_init.publish(generatePoseWithCov(2.0, 1.0));

ros::Rate wait(10);
for (int i = 0; i < 100; i++)
{
wait.sleep();
ros::spinOnce();
if (poses)
break;
ASSERT_TRUE(ros::ok());
}
ros::Duration(0.1).sleep();
ros::spinOnce();

Expand Down

0 comments on commit c170897

Please sign in to comment.