Skip to content

Commit

Permalink
planner_cspace: add costmap_cspace integration test for out-of-bound …
Browse files Browse the repository at this point in the history
…position (#746)
  • Loading branch information
at-wat authored Dec 25, 2024
1 parent 72e0ca8 commit d2eedce
Showing 1 changed file with 14 additions and 2 deletions.
16 changes: 14 additions & 2 deletions planner_cspace/test/src/test_navigate_boundary.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,11 @@
#include <ros/ros.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_ros/transform_broadcaster.h>
#include <nav_msgs/Path.h>
#include <actionlib/client/simple_action_client.h>

#include <move_base_msgs/MoveBaseAction.h>
#include <nav_msgs/Path.h>
#include <planner_cspace_msgs/PlannerStatus.h>

#include <gtest/gtest.h>

Expand All @@ -47,7 +49,9 @@ class NavigateBoundary : public ::testing::Test

ros::NodeHandle nh_;
tf2_ros::TransformBroadcaster tfb_;
ros::Subscriber sub_status_;
ros::Subscriber sub_path_;
planner_cspace_msgs::PlannerStatus::ConstPtr status_;
nav_msgs::Path::ConstPtr path_;
ActionClientPtr move_base_;

Expand All @@ -74,6 +78,7 @@ class NavigateBoundary : public ::testing::Test
}
virtual void SetUp()
{
sub_status_ = nh_.subscribe("/planner_3d/status", 100, &NavigateBoundary::cbStatus, this);
sub_path_ = nh_.subscribe("path", 1, &NavigateBoundary::cbPath, this);

publishTransform(1.0, 0.6);
Expand All @@ -92,6 +97,10 @@ class NavigateBoundary : public ::testing::Test
{
path_ = msg;
}
void cbStatus(const planner_cspace_msgs::PlannerStatus::ConstPtr& msg)
{
status_ = msg;
}
};

TEST_F(NavigateBoundary, StartPositionScan)
Expand All @@ -104,15 +113,18 @@ TEST_F(NavigateBoundary, StartPositionScan)
publishTransform(x, y);

path_ = nullptr;
status_ = nullptr;
for (int i = 0; i < 100; ++i)
{
ros::Duration(0.05).sleep();
ros::spinOnce();
if (path_)
if (path_ && status_)
break;
}
// Planner must publish at least empty path if alive.
ASSERT_TRUE(static_cast<bool>(path_));
// Planner status must be published even if robot if outside of the map.
ASSERT_TRUE(static_cast<bool>(status_));
}
}
}
Expand Down

0 comments on commit d2eedce

Please sign in to comment.