Skip to content

Commit

Permalink
Fix unintended changes
Browse files Browse the repository at this point in the history
  • Loading branch information
nhatao committed Jul 6, 2023
1 parent e144e4f commit 0f7c602
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 5 deletions.
2 changes: 2 additions & 0 deletions planner_cspace/src/patrol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,10 +130,12 @@ class PatrolActionNode
void spin()
{
ros::Rate rate(10.0);

while (ros::ok())
{
ros::spinOnce();
rate.sleep();

if (path_.poses.size() == 0)
{
continue;
Expand Down
6 changes: 1 addition & 5 deletions planner_cspace/test/src/test_navigate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,6 @@ class Navigate : public ::testing::Test
ros::Publisher pub_map_local_;
ros::Publisher pub_initial_pose_;
ros::Publisher pub_patrol_nodes_;

size_t local_map_apply_cnt_;
std::vector<tf2::Stamped<tf2::Transform>> traj_;
std::string test_scope_;
Expand Down Expand Up @@ -259,13 +258,12 @@ class Navigate : public ::testing::Test
{
ros::spinOnce();
ASSERT_TRUE(static_cast<bool>(map_));
// ASSERT_TRUE(static_cast<bool>(map_local_));
ASSERT_TRUE(static_cast<bool>(map_local_));
pubMapLocal();
ros::Duration(0.2).sleep();

ros::Rate wait(10);
ros::Time deadline = ros::Time::now() + ros::Duration(10);
bool planning_failed = false;
while (ros::ok())
{
pubMapLocal();
Expand All @@ -276,7 +274,6 @@ class Navigate : public ::testing::Test

if (now > deadline)
{
ROS_ERROR("FAILED");
dumpRobotTrajectory();
FAIL()
<< test_scope_ << "/" << name << ": Navigation timeout." << std::endl
Expand All @@ -286,7 +283,6 @@ class Navigate : public ::testing::Test

if (planner_status_->error == expected_error)
{
ROS_ERROR("SUCCEEDED");
return;
}
}
Expand Down

0 comments on commit 0f7c602

Please sign in to comment.