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 
83  const TestResultConstPtr &)
84 {
85  EXPECT_TRUE(ac->getState() == SimpleClientGoalState::SUCCEEDED)
86  << "Expected [SUCCEEDED], but getState() returned [" << ac->getState().toString() << "]";
87  EXPECT_TRUE(state == SimpleClientGoalState::SUCCEEDED)
88  << "Expected [SUCCEEDED], but goal state is [" << state.toString() << "]";
89  ros::Duration(0.1).sleep();
90  *called = true;
91 }
92 
93 TEST(SimpleClient, easy_callback)
94 {
96  SimpleActionClient<TestAction> client(n, "reference_action");
97 
98  bool started = client.waitForServer(ros::Duration(10.0));
99  ASSERT_TRUE(started);
100 
101  // sleep a bit to make sure that all topics are properly connected to the server.
102  ros::Duration(0.01).sleep();
103 
104  TestGoal goal;
105  bool finished;
106 
107  bool called = false;
108  goal.goal = 1;
109  SimpleActionClient<TestAction>::SimpleDoneCallback func = boost::bind(&easyDoneCallback, &called, &client, boost::placeholders::_1, boost::placeholders::_2);
110  client.sendGoal(goal, func);
111  finished = client.waitForResult(ros::Duration(10.0));
112  ASSERT_TRUE(finished);
113  EXPECT_TRUE(called) << "easyDoneCallback() was never called" ;
114 }
115 
117 {
118  ros::NodeHandle nh;
119  ros::spin();
120 }
121 
122 int main(int argc, char ** argv)
123 {
124  testing::InitGoogleTest(&argc, argv);
125 
126  ros::init(argc, argv, "simple_client_test");
127 
128  boost::thread spin_thread(&spinThread);
129 
130  int result = RUN_ALL_TESTS();
131 
132  ros::shutdown();
133 
134  spin_thread.join();
135 
136  return result;
137 }
main
int main(int argc, char **argv)
Definition: simple_client_test.cpp:122
spinThread
void spinThread()
Definition: simple_client_test.cpp:116
actionlib::SimpleClientGoalState::ABORTED
@ ABORTED
Definition: simple_client_goal_state.h:152
actionlib::SimpleActionClient::SimpleDoneCallback
boost::function< void(const SimpleClientGoalState &state, const ResultConstPtr &result)> SimpleDoneCallback
Definition: simple_action_client.h:81
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
actionlib::SimpleActionClient::waitForServer
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
Waits for the ActionServer to connect to this client.
Definition: simple_action_client.h:131
actionlib::SimpleClientGoalState
Definition: simple_client_goal_state.h:77
ros::shutdown
ROSCPP_DECL void shutdown()
actionlib::SimpleActionClient
A Simple client implementation of the ActionInterface which supports only one goal at a time.
Definition: simple_action_client.h:72
actionlib::SimpleClientGoalState::getText
std::string getText() const
Definition: simple_client_goal_state.h:171
actionlib::SimpleActionClient::sendGoal
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.
Definition: simple_action_client.h:317
actionlib::SimpleClientGoalState::SUCCEEDED
@ SUCCEEDED
Definition: simple_client_goal_state.h:153
actionlib::SimpleActionClient::cancelGoalsAtAndBeforeTime
void cancelGoalsAtAndBeforeTime(const ros::Time &time)
Cancel all goals that were stamped at and before the specified time.
Definition: simple_action_client.h:430
actionlib::SimpleActionClient::waitForResult
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
Blocks until this goal finishes.
Definition: simple_action_client.h:564
ros::Time
actionlib
Definition: action_definition.h:40
actionlib::SimpleClientGoalState::toString
std::string toString() const
Convert the state to a string. Useful when printing debugging information.
Definition: simple_client_goal_state.h:177
ros::spin
ROSCPP_DECL void spin()
easyDoneCallback
void easyDoneCallback(bool *called, SimpleActionClient< TestAction > *ac, const SimpleClientGoalState &state, const TestResultConstPtr &)
Definition: simple_client_test.cpp:82
simple_action_client.h
ros::Duration::sleep
bool sleep() const
actionlib::SimpleActionClient::getState
SimpleClientGoalState getState() const
Get the state information for this goal.
Definition: simple_action_client.h:338
actionlib::SimpleActionClient::cancelAllGoals
void cancelAllGoals()
Cancel all goals currently running on the action server.
Definition: simple_action_client.h:424
ros::Duration
ros::NodeHandle
TEST
TEST(SimpleClient, easy_tests)
Definition: simple_client_test.cpp:43


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55