simple_client_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
36 
37 #include <gtest/gtest.h>
38 #include <actionlib/TestAction.h>
40 
41 using namespace actionlib;
42 
43 TEST(SimpleClient, easy_tests) {
45  SimpleActionClient<TestAction> client(n, "reference_action");
46 
47  bool started = client.waitForServer(ros::Duration(10.0));
48  ASSERT_TRUE(started);
49 
50  TestGoal goal;
51  bool finished;
52 
53  goal.goal = 1;
54  // sleep a bit to make sure that all topics are properly connected to the server.
55  ros::Duration(0.01).sleep();
56  client.sendGoal(goal);
57  finished = client.waitForResult(ros::Duration(10.0));
58  ASSERT_TRUE(finished);
59  EXPECT_TRUE( client.getState() == SimpleClientGoalState::SUCCEEDED)
60  << "Expected [SUCCEEDED], but goal state is [" << client.getState().toString() << "]";
61 
62  // test that setting the text field for the status works
63  EXPECT_TRUE(client.getState().getText() == "The ref server has succeeded");
64 
65  goal.goal = 2;
66  client.sendGoal(goal);
67  finished = client.waitForResult(ros::Duration(10.0));
68  ASSERT_TRUE(finished);
69  EXPECT_TRUE( client.getState() == SimpleClientGoalState::ABORTED)
70  << "Expected [ABORTED], but goal state is [" << client.getState().toString() << "]";
71 
72  // test that setting the text field for the status works
73  EXPECT_TRUE(client.getState().getText() == "The ref server has aborted");
74 
75  client.cancelAllGoals();
76 
77  // Don't need this line, but keep it as a compilation check
79 }
80 
81 
82 void easyDoneCallback(bool * called, const SimpleClientGoalState & state,
83  const TestResultConstPtr &)
84 {
85  *called = true;
86  EXPECT_TRUE(state == SimpleClientGoalState::SUCCEEDED)
87  << "Expected [SUCCEEDED], but goal state is [" << state.toString() << "]";
88 }
89 
90 void easyOldDoneCallback(bool * called, const TerminalState & terminal_state,
91  const TestResultConstPtr &)
92 {
93  *called = true;
94  EXPECT_TRUE(terminal_state == TerminalState::SUCCEEDED)
95  << "Expected [SUCCEEDED], but terminal state is [" << terminal_state.toString() << "]";
96 }
97 
98 /* Intermittent failures #5087
99 TEST(SimpleClient, easy_callback)
100 {
101  ros::NodeHandle n;
102  SimpleActionClient<TestAction> client(n, "reference_action");
103 
104  bool started = client.waitForServer(ros::Duration(10.0));
105  ASSERT_TRUE(started);
106 
107  TestGoal goal;
108  bool finished;
109 
110  bool called = false;
111  goal.goal = 1;
112  SimpleActionClient<TestAction>::SimpleDoneCallback func = boost::bind(&easyDoneCallback, &called, _1, _2);
113  client.sendGoal(goal, func);
114  finished = client.waitForResult(ros::Duration(10.0));
115  ASSERT_TRUE(finished);
116  EXPECT_TRUE(called) << "easyDoneCallback() was never called" ;
117 }
118 */
120 {
121  ros::NodeHandle nh;
122  ros::spin();
123 }
124 
125 int main(int argc, char ** argv)
126 {
127  testing::InitGoogleTest(&argc, argv);
128 
129  ros::init(argc, argv, "simple_client_test");
130 
131  boost::thread spin_thread(&spinThread);
132 
133  int result = RUN_ALL_TESTS();
134 
135  ros::shutdown();
136 
137  spin_thread.join();
138 
139  return result;
140 }
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
Waits for the ActionServer to connect to this client.
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
Blocks until this goal finishes.
bool sleep() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void easyDoneCallback(bool *called, const SimpleClientGoalState &state, const TestResultConstPtr &)
std::string toString() const
Convert the state to a string. Useful when printing debugging information.
void spinThread()
void cancelGoalsAtAndBeforeTime(const ros::Time &time)
Cancel all goals that were stamped at and before the specified time.
ROSCPP_DECL void spin()
A Simple client implementation of the ActionInterface which supports only one goal at a time...
TEST(SimpleClient, easy_tests)
int main(int argc, char **argv)
void easyOldDoneCallback(bool *called, const TerminalState &terminal_state, const TestResultConstPtr &)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
Sends a goal to the ActionServer, and also registers callbacks.
ROSCPP_DECL void shutdown()
SimpleClientGoalState getState() const
Get the state information for this goal.
std::string toString() const
void cancelAllGoals()
Cancel all goals currently running on the action server.


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Aug 24 2020 03:40:47