test_navigate_boundary.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, 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 <cstddef>
31 #include <memory>
32 
33 #include <ros/ros.h>
37 
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>
42 
43 #include <gtest/gtest.h>
44 
45 class NavigateBoundary : public ::testing::Test
46 {
47 protected:
49  using ActionClientPtr = std::shared_ptr<ActionClient>;
50 
55  planner_cspace_msgs::PlannerStatus::ConstPtr status_;
56  nav_msgs::Path::ConstPtr path_;
58 
60  {
61  move_base_ = std::make_shared<ActionClient>("/move_base");
62  if (!move_base_->waitForServer(ros::Duration(10.0)))
63  {
64  ROS_ERROR("Failed to connect move_base action");
65  exit(EXIT_FAILURE);
66  }
67  }
68 
69  void publishTransform(const double x, const double y)
70  {
71  geometry_msgs::TransformStamped trans;
72  trans.header.stamp = ros::Time::now();
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;
78  tfb_.sendTransform(trans);
79  }
80  virtual void SetUp()
81  {
82  sub_status_ = nh_.subscribe("/planner_3d/status", 100, &NavigateBoundary::cbStatus, this);
83  sub_path_ = nh_.subscribe("path", 1, &NavigateBoundary::cbPath, this);
84 
85  publishTransform(1.0, 0.6);
86  ros::Duration(0.5).sleep();
87 
88  move_base_msgs::MoveBaseGoal goal;
89  goal.target_pose.header.frame_id = "map";
90  goal.target_pose.header.stamp = ros::Time::now();
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;
94  move_base_->sendGoal(goal);
95  ros::Duration(0.5).sleep();
96  }
97  void cbPath(const nav_msgs::Path::ConstPtr& msg)
98  {
99  path_ = msg;
100  }
101  void cbStatus(const planner_cspace_msgs::PlannerStatus::ConstPtr& msg)
102  {
103  status_ = msg;
104  }
105 };
106 
107 TEST_F(NavigateBoundary, StartPositionScan)
108 {
109  // map width/height is 32px * 0.1m = 3.2m
110  for (double x = -10; x < 13; x += 2.0)
111  {
112  for (double y = -10; y < 13; y += 2.0)
113  {
114  publishTransform(x, y);
115 
116  path_ = nullptr;
117  status_ = nullptr;
118  for (int i = 0; i < 100; ++i)
119  {
120  ros::Duration(0.05).sleep();
121  ros::spinOnce();
122  if (path_ && status_)
123  break;
124  }
125  // Planner must publish at least empty path if alive.
126  ASSERT_TRUE(static_cast<bool>(path_));
127  // Planner status must be published even if robot if outside of the map.
128  ASSERT_TRUE(static_cast<bool>(status_));
129  }
130  }
131 }
132 
133 TEST_F(NavigateBoundary, StartPositionScanWithTemporaryEscape)
134 {
135  ros::Publisher pub_trigger = nh_.advertise<std_msgs::Empty>("/planner_3d/temporary_escape", 1);
136 
137  // map width/height is 32px * 0.1m = 3.2m
138  for (double x = -10; x < 13; x += 2.0)
139  {
140  for (double y = -10; y < 13; y += 2.0)
141  {
142  publishTransform(x, y);
143 
144  path_ = nullptr;
145  status_ = nullptr;
146  for (int i = 0; i < 10; ++i)
147  {
148  std_msgs::Empty msg;
149  pub_trigger.publish(msg);
150 
151  ros::Duration(0.2).sleep();
152  ros::spinOnce();
153  if (path_ && status_)
154  break;
155  }
156  // Planner must publish at least empty path if alive.
157  ASSERT_TRUE(static_cast<bool>(path_));
158  // Planner status must be published even if robot if outside of the map.
159  ASSERT_TRUE(static_cast<bool>(status_));
160  }
161  }
162 }
163 
164 int main(int argc, char** argv)
165 {
166  testing::InitGoogleTest(&argc, argv);
167  ros::init(argc, argv, "test_navigate_boundary");
168 
169  return RUN_ALL_TESTS();
170 }
msg
msg
ros::Publisher
NavigateBoundary::cbStatus
void cbStatus(const planner_cspace_msgs::PlannerStatus::ConstPtr &msg)
Definition: test_navigate_boundary.cpp:101
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
NavigateBoundary::cbPath
void cbPath(const nav_msgs::Path::ConstPtr &msg)
Definition: test_navigate_boundary.cpp:97
NavigateBoundary::nh_
ros::NodeHandle nh_
Definition: test_navigate_boundary.cpp:51
ros::spinOnce
ROSCPP_DECL void spinOnce()
NavigateBoundary::move_base_
ActionClientPtr move_base_
Definition: test_navigate_boundary.cpp:57
NavigateBoundary::sub_path_
ros::Subscriber sub_path_
Definition: test_navigate_boundary.cpp:54
NavigateBoundary
Definition: test_navigate_boundary.cpp:45
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
transform_broadcaster.h
actionlib::SimpleActionClient
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
simple_action_client.h
NavigateBoundary::ActionClientPtr
std::shared_ptr< ActionClient > ActionClientPtr
Definition: test_navigate_boundary.cpp:49
NavigateBoundary::tfb_
tf2_ros::TransformBroadcaster tfb_
Definition: test_navigate_boundary.cpp:52
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
NavigateBoundary::sub_status_
ros::Subscriber sub_status_
Definition: test_navigate_boundary.cpp:53
NavigateBoundary::status_
planner_cspace_msgs::PlannerStatus::ConstPtr status_
Definition: test_navigate_boundary.cpp:55
NavigateBoundary::path_
nav_msgs::Path::ConstPtr path_
Definition: test_navigate_boundary.cpp:56
NavigateBoundary::publishTransform
void publishTransform(const double x, const double y)
Definition: test_navigate_boundary.cpp:69
ROS_ERROR
#define ROS_ERROR(...)
tf2_ros::TransformBroadcaster
tf2_geometry_msgs.h
ros::Duration::sleep
bool sleep() const
main
int main(int argc, char **argv)
Definition: test_navigate_boundary.cpp:164
NavigateBoundary::NavigateBoundary
NavigateBoundary()
Definition: test_navigate_boundary.cpp:59
TEST_F
TEST_F(NavigateBoundary, StartPositionScan)
Definition: test_navigate_boundary.cpp:107
ros::Duration
ros::NodeHandle
ros::Subscriber
ros::Time::now
static Time now()
NavigateBoundary::SetUp
virtual void SetUp()
Definition: test_navigate_boundary.cpp:80


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:23