test_preempt.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 <ros/ros.h>
00031 #include <actionlib/client/simple_action_client.h>
00032 #include <move_base_msgs/MoveBaseAction.h>
00033 #include <planner_cspace_msgs/PlannerStatus.h>
00034 
00035 #include <gtest/gtest.h>
00036 
00037 class PreemptTest : public ::testing::Test
00038 {
00039 public:
00040   PreemptTest()
00041     : node_()
00042   {
00043     move_base_ = std::make_shared<ActionClient>("/move_base");
00044     status_sub_ = node_.subscribe("/planner_3d/status",
00045                                   10,
00046                                   &PreemptTest::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   ~PreemptTest()
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 CreateGoalInFree()
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.24;
00072     goal.target_pose.pose.position.y = 0.65;
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 
00081   ros::NodeHandle node_;
00082   ros::Subscriber status_sub_;
00083   ActionClientPtr move_base_;
00084   planner_cspace_msgs::PlannerStatus status_;
00085 };
00086 
00087 TEST_F(PreemptTest, Preempt)
00088 {
00089   move_base_->sendGoal(CreateGoalInFree());
00090   while (move_base_->getState().state_ !=
00091          actionlib::SimpleClientGoalState::ACTIVE)
00092   {
00093     ros::Duration(1.0).sleep();
00094   }
00095   while (move_base_->getState().state_ ==
00096          actionlib::SimpleClientGoalState::ACTIVE)
00097   {
00098     move_base_->cancelAllGoals();
00099     ros::Duration(1.0).sleep();
00100   }
00101 
00102   ASSERT_EQ(actionlib::SimpleClientGoalState::PREEMPTED,
00103             move_base_->getState().state_);
00104   ASSERT_EQ(planner_cspace_msgs::PlannerStatus::GOING_WELL,
00105             status_.error);
00106   ASSERT_EQ(planner_cspace_msgs::PlannerStatus::DONE,
00107             status_.status);
00108 }
00109 
00110 int main(int argc, char** argv)
00111 {
00112   testing::InitGoogleTest(&argc, argv);
00113   ros::init(argc, argv, "test_preempt");
00114 
00115   ros::AsyncSpinner spinner(1);
00116   spinner.start();
00117   int ret = RUN_ALL_TESTS();
00118   spinner.stop();
00119   ros::shutdown();
00120   return ret;
00121 }


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