Skip to content

Commit

Permalink
Increase initialization timeout in the tests (#536)
Browse files Browse the repository at this point in the history
  • Loading branch information
at-wat committed Aug 3, 2020
1 parent bb5064b commit 85ce3da
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 2 deletions.
2 changes: 1 addition & 1 deletion joystick_interrupt/test/src/test_joystick_interrupt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,7 +274,7 @@ class JoystickMuxTest : public ::testing::Test
sub_ = nh_.subscribe("mux_output", 1, &JoystickMuxTest::cbMsg, this);

ros::Rate wait(10);
for (size_t i = 0; i < 20; ++i)
for (size_t i = 0; i < 100; ++i)
{
wait.sleep();
ros::spinOnce();
Expand Down
2 changes: 1 addition & 1 deletion track_odometry/test/src/test_track_odometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class TrackOdometryTest : public ::testing::TestWithParam<const char*>
ros::Duration(0.1).sleep();
ros::Rate rate(100);
odom_ = nullptr;
for (int i = 0; i < 100 && ros::ok(); ++i)
for (int i = 0; i < 1000 && ros::ok(); ++i)
{
odom_raw.header.stamp = ros::Time::now();
imu.header.stamp = odom_raw.header.stamp + ros::Duration(0.0001);
Expand Down
9 changes: 9 additions & 0 deletions trajectory_tracker/test/include/trajectory_tracker_test.h
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,15 @@ class TrajectoryTrackerTest : public ::testing::Test
pnh_.param("error_lin", error_lin_, 0.01);
pnh_.param("error_large_lin", error_large_lin_, 0.1);
pnh_.param("error_ang", error_ang_, 0.01);

ros::Rate wait(10);
for (size_t i = 0; i < 100; ++i)
{
wait.sleep();
ros::spinOnce();
if (pub_path_.getNumSubscribers() > 0)
break;
}
}
void initState(const Eigen::Vector2d& pos, const float yaw)
{
Expand Down

0 comments on commit 85ce3da

Please sign in to comment.