Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00036
00037 #include <gtest/gtest.h>
00038 #include <actionlib/TestAction.h>
00039 #include <actionlib/client/simple_action_client.h>
00040
00041 using namespace actionlib;
00042
00043 TEST(SimpleClient, easy_tests) {
00044 ros::NodeHandle n;
00045 SimpleActionClient<TestAction> client(n, "reference_action");
00046
00047 bool started = client.waitForServer(ros::Duration(10.0));
00048 ASSERT_TRUE(started);
00049
00050 TestGoal goal;
00051 bool finished;
00052
00053 goal.goal = 1;
00054
00055 ros::Duration(0.01).sleep();
00056 client.sendGoal(goal);
00057 finished = client.waitForResult(ros::Duration(10.0));
00058 ASSERT_TRUE(finished);
00059 EXPECT_TRUE( client.getState() == SimpleClientGoalState::SUCCEEDED)
00060 << "Expected [SUCCEEDED], but goal state is [" << client.getState().toString() << "]";
00061
00062
00063 EXPECT_TRUE(client.getState().getText() == "The ref server has succeeded");
00064
00065 goal.goal = 2;
00066 client.sendGoal(goal);
00067 finished = client.waitForResult(ros::Duration(10.0));
00068 ASSERT_TRUE(finished);
00069 EXPECT_TRUE( client.getState() == SimpleClientGoalState::ABORTED)
00070 << "Expected [ABORTED], but goal state is [" << client.getState().toString() << "]";
00071
00072
00073 EXPECT_TRUE(client.getState().getText() == "The ref server has aborted");
00074
00075 client.cancelAllGoals();
00076
00077
00078 client.cancelGoalsAtAndBeforeTime(ros::Time(1.0));
00079 }
00080
00081
00082 void easyDoneCallback(bool * called, const SimpleClientGoalState & state,
00083 const TestResultConstPtr &)
00084 {
00085 *called = true;
00086 EXPECT_TRUE(state == SimpleClientGoalState::SUCCEEDED)
00087 << "Expected [SUCCEEDED], but goal state is [" << state.toString() << "]";
00088 }
00089
00090 void easyOldDoneCallback(bool * called, const TerminalState & terminal_state,
00091 const TestResultConstPtr &)
00092 {
00093 *called = true;
00094 EXPECT_TRUE(terminal_state == TerminalState::SUCCEEDED)
00095 << "Expected [SUCCEEDED], but terminal state is [" << terminal_state.toString() << "]";
00096 }
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119 void spinThread()
00120 {
00121 ros::NodeHandle nh;
00122 ros::spin();
00123 }
00124
00125 int main(int argc, char ** argv)
00126 {
00127 testing::InitGoogleTest(&argc, argv);
00128
00129 ros::init(argc, argv, "simple_client_test");
00130
00131 boost::thread spin_thread(&spinThread);
00132
00133 int result = RUN_ALL_TESTS();
00134
00135 ros::shutdown();
00136
00137 spin_thread.join();
00138
00139 return result;
00140 }