34 #include <std_srvs/Empty.h> 35 #include <nav_msgs/Path.h> 36 #include <nav_msgs/GetPlan.h> 37 #include <nav_msgs/OccupancyGrid.h> 41 #include <gtest/gtest.h> 49 nav_msgs::OccupancyGrid::ConstPtr
map_;
64 nh_.
serviceClient<std_srvs::EmptyRequest, std_srvs::EmptyResponse>(
65 "forget_planning_cost");
66 pub_map_ = nh_.
advertise<nav_msgs::OccupancyGrid>(
"map", 1);
67 pub_map_local_ = nh_.
advertise<nav_msgs::OccupancyGrid>(
"overlay", 1);
69 nh_.
advertise<geometry_msgs::PoseWithCovarianceStamped>(
"initialpose", 1,
true);
74 geometry_msgs::PoseWithCovarianceStamped pose;
75 pose.header.frame_id =
"map";
76 pose.pose.pose.position.x = 2.5;
77 pose.pose.pose.position.y = 0.45;
78 pose.pose.pose.orientation.z = 1.0;
79 pub_initial_pose_.
publish(pose);
90 std::cerr <<
"Map applied." << std::endl;
92 std_srvs::EmptyRequest req;
93 std_srvs::EmptyResponse res;
94 srv_forget_.
call(req, res);
96 void cbMap(
const nav_msgs::OccupancyGrid::ConstPtr& msg)
99 std::cerr <<
"Map received." << std::endl;
101 void cbMapLocal(
const nav_msgs::OccupancyGrid::ConstPtr& msg)
104 std::cerr <<
"Local map received." << std::endl;
110 pub_map_local_.
publish(map_local_);
111 std::cerr <<
"Local map applied." << std::endl;
121 ASSERT_TRUE(static_cast<bool>(
map_));
124 path.poses.resize(2);
125 path.header.frame_id =
"map";
126 path.poses[0].header.frame_id = path.header.frame_id;
127 path.poses[0].pose.position.x = 1.7;
128 path.poses[0].pose.position.y = 2.8;
130 path.poses[1].header.frame_id = path.header.frame_id;
131 path.poses[1].pose.position.x = 1.9;
132 path.poses[1].pose.position.y = 2.8;
149 geometry_msgs::TransformStamped trans_tmp =
155 std::cerr << e.what() << std::endl;
159 auto goal_rel = trans.inverse() * goal;
160 if (goal_rel.getOrigin().length() < 0.2 &&
163 std::cerr <<
"Navagation success." << std::endl;
168 for (
int x = -2;
x <= 2; ++
x)
170 for (
int y = -1;
y <= 1; ++
y)
172 const tf2::Vector3 pos =
173 trans * tf2::Vector3(
x *
map_->info.resolution,
y *
map_->info.resolution, 0);
174 const int map_x = pos.x() /
map_->info.resolution;
175 const int map_y = pos.y() /
map_->info.resolution;
176 const size_t addr = map_x + map_y *
map_->info.width;
177 ASSERT_LT(addr,
map_->data.size());
178 ASSERT_LT(map_x, static_cast<int>(
map_->info.width));
179 ASSERT_LT(map_y, static_cast<int>(
map_->info.height));
182 ASSERT_NE(
map_->data[addr], 100);
194 ASSERT_TRUE(static_cast<bool>(
map_));
200 path.poses.resize(1);
201 path.header.frame_id =
"map";
202 path.poses[0].header.frame_id = path.header.frame_id;
203 path.poses[0].pose.position.x = 1.7;
204 path.poses[0].pose.position.y = 2.8;
221 geometry_msgs::TransformStamped trans_tmp =
227 std::cerr << e.what() << std::endl;
231 auto goal_rel = trans.inverse() * goal;
232 if (goal_rel.getOrigin().length() < 0.2 &&
235 std::cerr <<
"Navagation success." << std::endl;
240 for (
int x = -2;
x <= 2; ++
x)
242 for (
int y = -1;
y <= 1; ++
y)
244 const tf2::Vector3 pos =
245 trans * tf2::Vector3(
x *
map_->info.resolution,
y *
map_->info.resolution, 0);
246 const int map_x = pos.x() /
map_->info.resolution;
247 const int map_y = pos.y() /
map_->info.resolution;
248 const size_t addr = map_x + map_y *
map_->info.width;
249 ASSERT_LT(addr,
map_->data.size());
250 ASSERT_LT(map_x, static_cast<int>(
map_->info.width));
251 ASSERT_LT(map_y, static_cast<int>(
map_->info.height));
254 ASSERT_NE(
map_->data[addr], 100);
266 "/planner_3d/make_plan");
269 ASSERT_TRUE(static_cast<bool>(
map_));
271 nav_msgs::GetPlanRequest req;
272 nav_msgs::GetPlanResponse res;
274 req.start.header.frame_id =
"map";
275 req.start.pose.position.x = 2.0;
276 req.start.pose.position.y = 0.45;
277 req.start.pose.orientation =
280 req.goal.header.frame_id =
"map";
281 req.goal.pose.position.x = 1.2;
282 req.goal.pose.position.y = 1.9;
283 req.goal.pose.orientation =
285 ASSERT_FALSE(srv_plan.
call(req, res));
287 req.goal.header.frame_id =
"map";
288 req.goal.pose.position.x = 1.9;
289 req.goal.pose.position.y = 2.8;
290 req.goal.pose.orientation =
292 ASSERT_TRUE(srv_plan.
call(req, res));
294 ASSERT_NEAR(req.start.pose.position.x, res.plan.poses.front().pose.position.x, 0.1);
295 ASSERT_NEAR(req.start.pose.position.y, res.plan.poses.front().pose.position.y, 0.1);
296 ASSERT_NEAR(req.goal.pose.position.x, res.plan.poses.back().pose.position.x, 0.1);
297 ASSERT_NEAR(req.goal.pose.position.y, res.plan.poses.back().pose.position.y, 0.1);
299 for (
const geometry_msgs::PoseStamped& p : res.plan.poses)
301 const int map_x = p.pose.position.x /
map_->info.resolution;
302 const int map_y = p.pose.position.y /
map_->info.resolution;
303 const size_t addr = map_x + map_y *
map_->info.width;
304 ASSERT_LT(addr,
map_->data.size());
305 ASSERT_LT(map_x, static_cast<int>(
map_->info.width));
306 ASSERT_LT(map_y, static_cast<int>(
map_->info.height));
309 ASSERT_NE(
map_->data[addr], 100);
313 int main(
int argc,
char** argv)
315 testing::InitGoogleTest(&argc, argv);
318 return RUN_ALL_TESTS();
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void publish(const boost::shared_ptr< M > &message) const
void cbMap(const nav_msgs::OccupancyGrid::ConstPtr &msg)
nav_msgs::OccupancyGrid::ConstPtr map_
TEST_F(Navigate, Navigate)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
TFSIMD_FORCE_INLINE const tfScalar & y() const
ros::Subscriber sub_map_local_
nav_msgs::OccupancyGrid::ConstPtr map_local_
tf2_ros::TransformListener tfl_
ros::Publisher pub_initial_pose_
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
void fromMsg(const A &, B &b)
ros::ServiceClient srv_forget_
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double getYaw(const A &a)
ros::Publisher pub_map_local_
ROSCPP_DECL void spinOnce()
void cbMapLocal(const nav_msgs::OccupancyGrid::ConstPtr &msg)
int main(int argc, char **argv)