$search
00001 /* 00002 * Copyright (c) 2009, Willow Garage, Inc. 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 Willow Garage, Inc. 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 // Derived from excercise_simple_server.py 00031 00032 #include <gtest/gtest.h> 00033 #include <ros/ros.h> 00034 #include <actionlib/TestRequestAction.h> 00035 #include <actionlib/TestRequestGoal.h> 00036 #include <actionlib/client/simple_action_client.h> 00037 #include <actionlib_msgs/GoalStatus.h> 00038 00039 00040 #define EXPECT_STATE(expected_state) EXPECT_TRUE( ac_.getState() == SimpleClientGoalState::expected_state) \ 00041 << "Expected [" << #expected_state << "], but goal state is [" << ac_.getState().toString() << "]"; 00042 00043 00044 using namespace actionlib; 00045 using namespace actionlib_msgs; 00046 00047 class SimpleClientFixture : public testing::Test 00048 { 00049 public: 00050 SimpleClientFixture() : ac_("test_request_action"), default_wait_(60.0) { } 00051 00052 protected: 00053 virtual void SetUp() 00054 { 00055 // Make sure that the server comes up 00056 ASSERT_TRUE( ac_.waitForServer(ros::Duration(10.0)) ); 00057 } 00058 00059 SimpleActionClient<TestRequestAction> ac_; 00060 ros::Duration default_wait_; 00061 }; 00062 00063 TEST_F(SimpleClientFixture, just_succeed) 00064 { 00065 TestRequestGoal goal; 00066 goal.terminate_status = TestRequestGoal::TERMINATE_SUCCESS; 00067 goal.the_result = 42; 00068 ac_.sendGoal(goal); 00069 ac_.waitForResult(default_wait_); 00070 EXPECT_STATE(SUCCEEDED); 00071 EXPECT_EQ(42, ac_.getResult()->the_result); 00072 } 00073 00074 TEST_F(SimpleClientFixture, just_abort) 00075 { 00076 TestRequestGoal goal; 00077 goal.terminate_status = TestRequestGoal::TERMINATE_ABORTED; 00078 goal.the_result = 42; 00079 ac_.sendGoal(goal); 00080 ac_.waitForResult(default_wait_); 00081 EXPECT_STATE(ABORTED); 00082 EXPECT_EQ(42, ac_.getResult()->the_result); 00083 } 00084 00085 TEST_F(SimpleClientFixture, just_preempt) 00086 { 00087 TestRequestGoal goal; 00088 goal.terminate_status = TestRequestGoal::TERMINATE_SUCCESS; 00089 goal.delay_terminate = ros::Duration(1000); 00090 goal.the_result = 42; 00091 ac_.sendGoal(goal); 00092 00093 // Sleep for 10 seconds or until we hear back from the action server 00094 for (unsigned int i=0; i < 100; i++) 00095 { 00096 ROS_DEBUG_NAMED("actionlib", "Waiting for Server Response"); 00097 if (ac_.getState() != SimpleClientGoalState::PENDING) 00098 break; 00099 ros::Duration(0.1).sleep(); 00100 } 00101 00102 ac_.cancelGoal(); 00103 ac_.waitForResult(default_wait_); 00104 EXPECT_STATE(PREEMPTED); 00105 EXPECT_EQ(42, ac_.getResult()->the_result); 00106 } 00107 00108 TEST_F(SimpleClientFixture, drop) 00109 { 00110 TestRequestGoal goal; 00111 goal.terminate_status = TestRequestGoal::TERMINATE_DROP; 00112 goal.the_result = 42; 00113 ac_.sendGoal(goal); 00114 ac_.waitForResult(default_wait_); 00115 EXPECT_STATE(ABORTED); 00116 EXPECT_EQ(0, ac_.getResult()->the_result); 00117 } 00118 00119 TEST_F(SimpleClientFixture, exception) 00120 { 00121 TestRequestGoal goal; 00122 goal.terminate_status = TestRequestGoal::TERMINATE_EXCEPTION; 00123 goal.the_result = 42; 00124 ac_.sendGoal(goal); 00125 ac_.waitForResult(default_wait_); 00126 EXPECT_STATE(ABORTED); 00127 EXPECT_EQ(0, ac_.getResult()->the_result); 00128 } 00129 00130 TEST_F(SimpleClientFixture, ignore_cancel_and_succeed) 00131 { 00132 TestRequestGoal goal; 00133 goal.terminate_status = TestRequestGoal::TERMINATE_SUCCESS; 00134 goal.delay_terminate = ros::Duration(2.0); 00135 goal.ignore_cancel = true; 00136 goal.the_result = 42; 00137 ac_.sendGoal(goal); 00138 00139 // Sleep for 10 seconds or until we hear back from the action server 00140 for (unsigned int i=0; i < 100; i++) 00141 { 00142 ROS_DEBUG_NAMED("actionlib", "Waiting for Server Response"); 00143 if (ac_.getState() != SimpleClientGoalState::PENDING) 00144 break; 00145 ros::Duration(0.1).sleep(); 00146 } 00147 00148 ac_.cancelGoal(); 00149 ac_.waitForResult(default_wait_ + default_wait_); 00150 EXPECT_STATE(SUCCEEDED); 00151 EXPECT_EQ(42, ac_.getResult()->the_result); 00152 } 00153 00154 TEST_F(SimpleClientFixture, lose) 00155 { 00156 TestRequestGoal goal; 00157 goal.terminate_status = TestRequestGoal::TERMINATE_LOSE; 00158 goal.the_result = 42; 00159 ac_.sendGoal(goal); 00160 ac_.waitForResult(default_wait_); 00161 EXPECT_STATE(LOST); 00162 } 00163 00164 void spinThread() 00165 { 00166 ros::NodeHandle nh; 00167 ros::spin(); 00168 } 00169 00170 int main(int argc, char **argv){ 00171 testing::InitGoogleTest(&argc, argv); 00172 00173 ros::init(argc, argv, "simple_client_test"); 00174 00175 boost::thread spin_thread(&spinThread); 00176 00177 int result = RUN_ALL_TESTS(); 00178 00179 ros::shutdown(); 00180 00181 spin_thread.join(); 00182 00183 return result; 00184 }