test_navigate.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 #include <tf2/utils.h>
34 #include <std_srvs/Empty.h>
35 #include <nav_msgs/Path.h>
36 #include <nav_msgs/GetPlan.h>
37 #include <nav_msgs/OccupancyGrid.h>
38 
39 #include <cstddef>
40 
41 #include <gtest/gtest.h>
42 
43 class Navigate : public ::testing::Test
44 {
45 protected:
49  nav_msgs::OccupancyGrid::ConstPtr map_;
50  nav_msgs::OccupancyGrid::ConstPtr map_local_;
57 
59  : tfl_(tfbuf_)
60  {
61  sub_map_ = nh_.subscribe("map_global", 1, &Navigate::cbMap, this);
62  sub_map_local_ = nh_.subscribe("map_local", 1, &Navigate::cbMapLocal, this);
63  srv_forget_ =
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);
68  pub_initial_pose_ =
69  nh_.advertise<geometry_msgs::PoseWithCovarianceStamped>("initialpose", 1, true);
70  }
71 
72  virtual void SetUp()
73  {
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);
80 
81  srv_forget_.waitForExistence(ros::Duration(2.0));
82  ros::Rate rate(10.0);
83 
84  while (ros::ok() && !map_)
85  {
86  ros::spinOnce();
87  rate.sleep();
88  }
89  pub_map_.publish(map_);
90  std::cerr << "Map applied." << std::endl;
91 
92  std_srvs::EmptyRequest req;
93  std_srvs::EmptyResponse res;
94  srv_forget_.call(req, res);
95  }
96  void cbMap(const nav_msgs::OccupancyGrid::ConstPtr& msg)
97  {
98  map_ = msg;
99  std::cerr << "Map received." << std::endl;
100  }
101  void cbMapLocal(const nav_msgs::OccupancyGrid::ConstPtr& msg)
102  {
103  map_local_ = msg;
104  std::cerr << "Local map received." << std::endl;
105  }
106  void pubMapLocal()
107  {
108  if (map_local_)
109  {
110  pub_map_local_.publish(map_local_);
111  std::cerr << "Local map applied." << std::endl;
112  }
113  }
114 };
115 
117 {
118  ros::Publisher pub_path = nh_.advertise<nav_msgs::Path>("patrol_nodes", 1, true);
119 
120  ros::spinOnce();
121  ASSERT_TRUE(static_cast<bool>(map_));
122 
123  nav_msgs::Path path;
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;
129  path.poses[0].pose.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), -3.14));
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;
133  path.poses[1].pose.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), -1.57));
134  pub_path.publish(path);
135 
136  tf2::Transform goal;
137  tf2::fromMsg(path.poses.back().pose, goal);
138 
139  ros::Rate wait(10);
140  while (ros::ok())
141  {
142  ros::spinOnce();
143  wait.sleep();
144 
146  try
147  {
148  const ros::Time now = ros::Time::now();
149  geometry_msgs::TransformStamped trans_tmp =
150  tfbuf_.lookupTransform("map", "base_link", now, ros::Duration(0.5));
151  tf2::fromMsg(trans_tmp, trans);
152  }
153  catch (tf2::TransformException& e)
154  {
155  std::cerr << e.what() << std::endl;
156  continue;
157  }
158 
159  auto goal_rel = trans.inverse() * goal;
160  if (goal_rel.getOrigin().length() < 0.2 &&
161  fabs(tf2::getYaw(goal_rel.getRotation())) < 0.2)
162  {
163  std::cerr << "Navagation success." << std::endl;
164  ros::Duration(2.0).sleep();
165  return;
166  }
167 
168  for (int x = -2; x <= 2; ++x)
169  {
170  for (int y = -1; y <= 1; ++y)
171  {
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));
180  ASSERT_GE(map_x, 0);
181  ASSERT_GE(map_y, 0);
182  ASSERT_NE(map_->data[addr], 100);
183  }
184  }
185  }
186  ASSERT_TRUE(false);
187 }
188 
189 TEST_F(Navigate, NavigateWithLocalMap)
190 {
191  ros::Publisher pub_path = nh_.advertise<nav_msgs::Path>("patrol_nodes", 1, true);
192 
193  ros::spinOnce();
194  ASSERT_TRUE(static_cast<bool>(map_));
195  ASSERT_TRUE(static_cast<bool>(map_local_));
196  pubMapLocal();
197  ros::Duration(0.2).sleep();
198 
199  nav_msgs::Path path;
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;
205  path.poses[0].pose.orientation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), -3.14));
206  pub_path.publish(path);
207 
208  tf2::Transform goal;
209  tf2::fromMsg(path.poses.back().pose, goal);
210 
211  ros::Rate wait(10);
212  while (ros::ok())
213  {
214  ros::spinOnce();
215  wait.sleep();
216 
218  try
219  {
220  const ros::Time now = ros::Time::now();
221  geometry_msgs::TransformStamped trans_tmp =
222  tfbuf_.lookupTransform("map", "base_link", now, ros::Duration(0.5));
223  tf2::fromMsg(trans_tmp, trans);
224  }
225  catch (tf2::TransformException& e)
226  {
227  std::cerr << e.what() << std::endl;
228  continue;
229  }
230 
231  auto goal_rel = trans.inverse() * goal;
232  if (goal_rel.getOrigin().length() < 0.2 &&
233  fabs(tf2::getYaw(goal_rel.getRotation())) < 0.2)
234  {
235  std::cerr << "Navagation success." << std::endl;
236  ros::Duration(2.0).sleep();
237  return;
238  }
239 
240  for (int x = -2; x <= 2; ++x)
241  {
242  for (int y = -1; y <= 1; ++y)
243  {
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));
252  ASSERT_GE(map_x, 0);
253  ASSERT_GE(map_y, 0);
254  ASSERT_NE(map_->data[addr], 100);
255  ASSERT_NE(map_local_->data[addr], 100);
256  }
257  }
258  }
259  ASSERT_TRUE(false);
260 }
261 
262 TEST_F(Navigate, GlobalPlan)
263 {
264  ros::ServiceClient srv_plan =
265  nh_.serviceClient<nav_msgs::GetPlanRequest, nav_msgs::GetPlanResponse>(
266  "/planner_3d/make_plan");
267 
268  ros::spinOnce();
269  ASSERT_TRUE(static_cast<bool>(map_));
270 
271  nav_msgs::GetPlanRequest req;
272  nav_msgs::GetPlanResponse res;
273 
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 =
278  tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), 3.14));
279 
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 =
284  tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), -3.14));
285  ASSERT_FALSE(srv_plan.call(req, res));
286 
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 =
291  tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), -1.57));
292  ASSERT_TRUE(srv_plan.call(req, res));
293 
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);
298 
299  for (const geometry_msgs::PoseStamped& p : res.plan.poses)
300  {
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));
307  ASSERT_GE(map_x, 0);
308  ASSERT_GE(map_y, 0);
309  ASSERT_NE(map_->data[addr], 100);
310  }
311 }
312 
313 int main(int argc, char** argv)
314 {
315  testing::InitGoogleTest(&argc, argv);
316  ros::init(argc, argv, "test_navigate");
317 
318  return RUN_ALL_TESTS();
319 }
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())
bool sleep() const
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)
ros::Publisher pub_map_
TFSIMD_FORCE_INLINE const tfScalar & y() const
ros::Subscriber sub_map_local_
ros::Subscriber sub_map_
void pubMapLocal()
nav_msgs::OccupancyGrid::ConstPtr map_local_
tf2_ros::TransformListener tfl_
ros::NodeHandle nh_
ros::Publisher pub_initial_pose_
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
void fromMsg(const A &, B &b)
ROSCPP_DECL bool ok()
ros::ServiceClient srv_forget_
tf2_ros::Buffer tfbuf_
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool sleep()
double getYaw(const A &a)
B toMsg(const A &a)
virtual void SetUp()
static Time now()
ros::Publisher pub_map_local_
ROSCPP_DECL void spinOnce()
void cbMapLocal(const nav_msgs::OccupancyGrid::ConstPtr &msg)
int main(int argc, char **argv)


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:13