test_abort.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2018, the neonavigation authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <actionlib/client/simple_action_client.h>
00031 #include <gtest/gtest.h>
00032 #include <move_base_msgs/MoveBaseAction.h>
00033 #include <planner_cspace_msgs/PlannerStatus.h>
00034 #include <ros/ros.h>
00035 #include <memory>
00036 
00037 class AbortTest : public ::testing::Test
00038 {
00039 public:
00040   AbortTest()
00041     : node_()
00042   {
00043     move_base_ = std::make_shared<ActionClient>("/move_base");
00044     status_sub_ = node_.subscribe("/planner_3d/status",
00045                                   10,
00046                                   &AbortTest::StatusCallback,
00047                                   this);
00048     if (!move_base_->waitForServer(ros::Duration(30.0)))
00049     {
00050       ROS_ERROR("Failed to connect move_base action");
00051       exit(EXIT_FAILURE);
00052     }
00053   }
00054   ~AbortTest()
00055   {
00056   }
00057 
00058 protected:
00059   using ActionClient = actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>;
00060   using ActionClientPtr = std::shared_ptr<ActionClient>;
00061 
00062   void StatusCallback(const planner_cspace_msgs::PlannerStatus& msg)
00063   {
00064     status_ = msg;
00065   }
00066   move_base_msgs::MoveBaseGoal CreateGoalInRock()
00067   {
00068     move_base_msgs::MoveBaseGoal goal;
00069     goal.target_pose.header.stamp = ros::Time::now();
00070     goal.target_pose.header.frame_id = "map";
00071     goal.target_pose.pose.position.x = 1.19;
00072     goal.target_pose.pose.position.y = 1.90;
00073     goal.target_pose.pose.position.z = 0.0;
00074     goal.target_pose.pose.orientation.x = 0.0;
00075     goal.target_pose.pose.orientation.y = 0.0;
00076     goal.target_pose.pose.orientation.z = 0.0;
00077     goal.target_pose.pose.orientation.w = 1.0;
00078     return goal;
00079   }
00080   move_base_msgs::MoveBaseGoal CreateGoalInFree()
00081   {
00082     move_base_msgs::MoveBaseGoal goal;
00083     goal.target_pose.header.stamp = ros::Time::now();
00084     goal.target_pose.header.frame_id = "map";
00085     goal.target_pose.pose.position.x = 1.24;
00086     goal.target_pose.pose.position.y = 0.65;
00087     goal.target_pose.pose.position.z = 0.0;
00088     goal.target_pose.pose.orientation.x = 0.0;
00089     goal.target_pose.pose.orientation.y = 0.0;
00090     goal.target_pose.pose.orientation.z = 0.0;
00091     goal.target_pose.pose.orientation.w = 1.0;
00092     return goal;
00093   }
00094 
00095   ros::NodeHandle node_;
00096   ros::Subscriber status_sub_;
00097   ActionClientPtr move_base_;
00098   planner_cspace_msgs::PlannerStatus status_;
00099 };
00100 
00101 TEST_F(AbortTest, AbortByGoalInRock)
00102 {
00103   // Send a goal which is in Rock
00104   move_base_->sendGoal(CreateGoalInRock());
00105   while (move_base_->getState().state_ !=
00106          actionlib::SimpleClientGoalState::ACTIVE)
00107   {
00108     ros::Duration(1.0).sleep();
00109   }
00110 
00111   // Try to replan
00112   while (move_base_->getState().state_ ==
00113          actionlib::SimpleClientGoalState::ACTIVE)
00114   {
00115     ros::Duration(1.0).sleep();
00116   }
00117   ros::Duration(1.0).sleep();
00118 
00119   // Abort after exceeding max_retry_num
00120   ASSERT_EQ(actionlib::SimpleClientGoalState::ABORTED,
00121             move_base_->getState().state_);
00122   ASSERT_EQ(planner_cspace_msgs::PlannerStatus::PATH_NOT_FOUND,
00123             status_.error);
00124 
00125   // Send another goal which is not in Rock
00126   move_base_->sendGoal(CreateGoalInFree());
00127   while (move_base_->getState().state_ !=
00128          actionlib::SimpleClientGoalState::ACTIVE)
00129   {
00130     ros::Duration(1.0).sleep();
00131   }
00132   while (move_base_->getState().state_ ==
00133          actionlib::SimpleClientGoalState::ACTIVE)
00134   {
00135     ros::Duration(1.0).sleep();
00136   }
00137   ros::Duration(1.0).sleep();
00138 
00139   // Succeed
00140   ASSERT_EQ(actionlib::SimpleClientGoalState::SUCCEEDED,
00141             move_base_->getState().state_);
00142   ASSERT_EQ(planner_cspace_msgs::PlannerStatus::GOING_WELL,
00143             status_.error);
00144 }
00145 
00146 int main(int argc, char** argv)
00147 {
00148   testing::InitGoogleTest(&argc, argv);
00149   ros::init(argc, argv, "test_abort");
00150 
00151   ros::AsyncSpinner spinner(1);
00152   spinner.start();
00153   int ret = RUN_ALL_TESTS();
00154   spinner.stop();
00155   ros::shutdown();
00156   return ret;
00157 }


planner_cspace
Author(s): Atsushi Watanabe
autogenerated on Sat Jun 22 2019 20:07:27