test_abort.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018, 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 <memory>
31 #include <string>
32 
33 #include <gtest/gtest.h>
34 
36 #include <move_base_msgs/MoveBaseAction.h>
37 #include <planner_cspace_msgs/PlannerStatus.h>
38 #include <ros/ros.h>
39 
41 
42 class AbortTest
43  : public ActionTestBase<move_base_msgs::MoveBaseAction, ACTION_TOPIC_MOVE_BASE>
44 {
45 protected:
46  move_base_msgs::MoveBaseGoal createGoalInRock()
47  {
48  move_base_msgs::MoveBaseGoal goal;
49  goal.target_pose.header.stamp = ros::Time::now();
50  goal.target_pose.header.frame_id = "map";
51  goal.target_pose.pose.position.x = 1.19;
52  goal.target_pose.pose.position.y = 1.90;
53  goal.target_pose.pose.position.z = 0.0;
54  goal.target_pose.pose.orientation.x = 0.0;
55  goal.target_pose.pose.orientation.y = 0.0;
56  goal.target_pose.pose.orientation.z = 0.0;
57  goal.target_pose.pose.orientation.w = 1.0;
58  return goal;
59  }
60  move_base_msgs::MoveBaseGoal createGoalInFree()
61  {
62  move_base_msgs::MoveBaseGoal goal;
63  goal.target_pose.header.stamp = ros::Time::now();
64  goal.target_pose.header.frame_id = "map";
65  goal.target_pose.pose.position.x = 2.1;
66  goal.target_pose.pose.position.y = 0.45;
67  goal.target_pose.pose.position.z = 0.0;
68  goal.target_pose.pose.orientation.x = 0.0;
69  goal.target_pose.pose.orientation.y = 0.0;
70  goal.target_pose.pose.orientation.z = 1.0;
71  goal.target_pose.pose.orientation.w = 0.0;
72  return goal;
73  }
74 };
75 
76 TEST_F(AbortTest, AbortByGoalInRock)
77 {
78  const ros::Time deadline = ros::Time::now() + ros::Duration(10);
79  const ros::Duration wait(1.0);
80 
81  // Assure that goal is received after map in planner_3d.
82  ros::Duration(0.5).sleep();
83  // Send a goal which is in Rock
84  move_base_->sendGoal(createGoalInRock());
85  while (move_base_->getState().state_ !=
87  {
88  wait.sleep();
89  ASSERT_LT(ros::Time::now(), deadline)
90  << "Action didn't get active: " << move_base_->getState().toString()
91  << " " << statusString();
92  }
93 
94  // Try to replan
95  while (move_base_->getState().state_ ==
97  {
98  wait.sleep();
99  ASSERT_LT(ros::Time::now(), deadline)
100  << "Action didn't get inactive: " << move_base_->getState().toString()
101  << " " << statusString();
102  }
103  wait.sleep();
104 
105  ASSERT_TRUE(planner_status_);
106 
107  // Abort after exceeding max_retry_num
109  move_base_->getState().state_);
110  ASSERT_EQ(planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND,
111  planner_status_->error);
112 
113  // Send another goal which is not in Rock
114  move_base_->sendGoal(createGoalInFree());
115  while (move_base_->getState().state_ !=
117  {
118  wait.sleep();
119  ASSERT_LT(ros::Time::now(), deadline)
120  << "Action didn't get active: " << move_base_->getState().toString()
121  << " " << statusString();
122  }
123  while (move_base_->getState().state_ ==
125  {
126  wait.sleep();
127  ASSERT_LT(ros::Time::now(), deadline)
128  << "Action didn't get inactive: " << move_base_->getState().toString()
129  << " " << statusString();
130  }
131  wait.sleep();
132 
133  // Succeed
135  move_base_->getState().state_);
136  ASSERT_EQ(planner_cspace_msgs::PlannerStatus::GOING_WELL,
137  planner_status_->error);
138 }
139 
140 int main(int argc, char** argv)
141 {
142  testing::InitGoogleTest(&argc, argv);
143  ros::init(argc, argv, "test_abort");
144 
146  spinner.start();
147  int ret = RUN_ALL_TESTS();
148  spinner.stop();
149  ros::shutdown();
150  return ret;
151 }
int main(int argc, char **argv)
Definition: test_abort.cpp:140
void wait(int seconds)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void spinner()
TEST_F(AbortTest, AbortByGoalInRock)
Definition: test_abort.cpp:76
move_base_msgs::MoveBaseGoal createGoalInRock()
Definition: test_abort.cpp:46
move_base_msgs::MoveBaseGoal createGoalInFree()
Definition: test_abort.cpp:60
static Time now()
ROSCPP_DECL void shutdown()
bool sleep() const


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 3 2023 02:39:06