38 #include <move_base_msgs/MoveBaseAction.h>
39 #include <nav_msgs/Path.h>
40 #include <planner_cspace_msgs/PlannerStatus.h>
41 #include <std_msgs/Empty.h>
43 #include <gtest/gtest.h>
55 planner_cspace_msgs::PlannerStatus::ConstPtr
status_;
61 move_base_ = std::make_shared<ActionClient>(
"/move_base");
64 ROS_ERROR(
"Failed to connect move_base action");
71 geometry_msgs::TransformStamped trans;
73 trans.header.frame_id =
"odom";
74 trans.child_frame_id =
"base_link";
75 trans.transform.translation.x = x;
76 trans.transform.translation.y = y;
77 trans.transform.rotation.w = 1.0;
88 move_base_msgs::MoveBaseGoal goal;
89 goal.target_pose.header.frame_id =
"map";
91 goal.target_pose.pose.orientation.w = 1;
92 goal.target_pose.pose.position.x = 1.4;
93 goal.target_pose.pose.position.y = 0.6;
97 void cbPath(
const nav_msgs::Path::ConstPtr& msg)
101 void cbStatus(
const planner_cspace_msgs::PlannerStatus::ConstPtr& msg)
110 for (
double x = -10; x < 13; x += 2.0)
112 for (
double y = -10; y < 13; y += 2.0)
114 publishTransform(x, y);
118 for (
int i = 0; i < 100; ++i)
122 if (path_ && status_)
126 ASSERT_TRUE(
static_cast<bool>(path_));
128 ASSERT_TRUE(
static_cast<bool>(status_));
135 ros::Publisher pub_trigger = nh_.advertise<std_msgs::Empty>(
"/planner_3d/temporary_escape", 1);
138 for (
double x = -10; x < 13; x += 2.0)
140 for (
double y = -10; y < 13; y += 2.0)
142 publishTransform(x, y);
146 for (
int i = 0; i < 10; ++i)
153 if (path_ && status_)
157 ASSERT_TRUE(
static_cast<bool>(path_));
159 ASSERT_TRUE(
static_cast<bool>(status_));
164 int main(
int argc,
char** argv)
166 testing::InitGoogleTest(&argc, argv);
167 ros::init(argc, argv,
"test_navigate_boundary");
169 return RUN_ALL_TESTS();