exercise_simple_client.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 // Derived from exercise_simple_server.py
31 
32 #include <gtest/gtest.h>
33 #include <ros/ros.h>
34 #include <actionlib/TestRequestAction.h>
35 #include <actionlib/TestRequestGoal.h>
37 #include <actionlib_msgs/GoalStatus.h>
38 
39 
40 #define EXPECT_STATE(expected_state) EXPECT_TRUE( \
41  ac_.getState() == SimpleClientGoalState::expected_state) \
42  << "Expected [" << #expected_state << "], but goal state is [" << ac_.getState().toString() << \
43  "]";
44 
45 
46 using namespace actionlib;
47 using namespace actionlib_msgs;
48 
49 class SimpleClientFixture : public testing::Test
50 {
51 public:
53  : ac_("test_request_action"), default_wait_(60.0) {}
54 
55 protected:
56  virtual void SetUp()
57  {
58  // Make sure that the server comes up
59  ASSERT_TRUE(ac_.waitForServer(ros::Duration(10.0)) );
60  }
61 
64 };
65 
66 TEST_F(SimpleClientFixture, just_succeed) {
67  TestRequestGoal goal;
68  goal.terminate_status = TestRequestGoal::TERMINATE_SUCCESS;
69  goal.the_result = 42;
70  ac_.sendGoal(goal);
71  ac_.waitForResult(default_wait_);
72  EXPECT_STATE(SUCCEEDED);
73  EXPECT_EQ(42, ac_.getResult()->the_result);
74 }
75 
77  TestRequestGoal goal;
78  goal.terminate_status = TestRequestGoal::TERMINATE_ABORTED;
79  goal.the_result = 42;
80  ac_.sendGoal(goal);
81  ac_.waitForResult(default_wait_);
82  EXPECT_STATE(ABORTED);
83  EXPECT_EQ(42, ac_.getResult()->the_result);
84 }
85 
86 TEST_F(SimpleClientFixture, just_preempt) {
87  TestRequestGoal goal;
88  goal.terminate_status = TestRequestGoal::TERMINATE_SUCCESS;
89  goal.delay_terminate = ros::Duration(1000);
90  goal.the_result = 42;
91  ac_.sendGoal(goal);
92 
93  // Sleep for 10 seconds or until we hear back from the action server
94  for (unsigned int i = 0; i < 100; i++) {
95  ROS_DEBUG_NAMED("actionlib", "Waiting for Server Response");
96  if (ac_.getState() != SimpleClientGoalState::PENDING) {
97  break;
98  }
99  ros::Duration(0.1).sleep();
100  }
101 
102  ac_.cancelGoal();
103  ac_.waitForResult(default_wait_);
104  EXPECT_STATE(PREEMPTED);
105  EXPECT_EQ(42, ac_.getResult()->the_result);
106 }
107 
109  TestRequestGoal goal;
110  goal.terminate_status = TestRequestGoal::TERMINATE_DROP;
111  goal.the_result = 42;
112  ac_.sendGoal(goal);
113  ac_.waitForResult(default_wait_);
114  EXPECT_STATE(ABORTED);
115  EXPECT_EQ(0, ac_.getResult()->the_result);
116 }
117 
119  TestRequestGoal goal;
120  goal.terminate_status = TestRequestGoal::TERMINATE_EXCEPTION;
121  goal.the_result = 42;
122  ac_.sendGoal(goal);
123  ac_.waitForResult(default_wait_);
124  EXPECT_STATE(ABORTED);
125  EXPECT_EQ(0, ac_.getResult()->the_result);
126 }
127 
128 TEST_F(SimpleClientFixture, ignore_cancel_and_succeed) {
129  TestRequestGoal goal;
130  goal.terminate_status = TestRequestGoal::TERMINATE_SUCCESS;
131  goal.delay_terminate = ros::Duration(2.0);
132  goal.ignore_cancel = true;
133  goal.the_result = 42;
134  ac_.sendGoal(goal);
135 
136  // Sleep for 10 seconds or until we hear back from the action server
137  for (unsigned int i = 0; i < 100; i++) {
138  ROS_DEBUG_NAMED("actionlib", "Waiting for Server Response");
139  if (ac_.getState() != SimpleClientGoalState::PENDING) {
140  break;
141  }
142  ros::Duration(0.1).sleep();
143  }
144 
145  ac_.cancelGoal();
146  ac_.waitForResult(default_wait_ + default_wait_);
147  EXPECT_STATE(SUCCEEDED);
148  EXPECT_EQ(42, ac_.getResult()->the_result);
149 }
150 
152  TestRequestGoal goal;
153  goal.terminate_status = TestRequestGoal::TERMINATE_LOSE;
154  goal.the_result = 42;
155  ac_.sendGoal(goal);
156  ac_.waitForResult(default_wait_);
157  EXPECT_STATE(LOST);
158 }
159 
161 {
162  ros::NodeHandle nh;
163  ros::spin();
164 }
165 
166 int main(int argc, char ** argv)
167 {
168  testing::InitGoogleTest(&argc, argv);
169 
170  ros::init(argc, argv, "simple_client_test");
171 
172  boost::thread spin_thread(&spinThread);
173 
174  int result = RUN_ALL_TESTS();
175 
176  ros::shutdown();
177 
178  spin_thread.join();
179 
180  return result;
181 }
SimpleClientFixture::SimpleClientFixture
SimpleClientFixture()
Definition: exercise_simple_client.cpp:52
EXPECT_STATE
#define EXPECT_STATE(expected_state)
Definition: exercise_simple_client.cpp:40
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
SimpleClientFixture::ac_
SimpleActionClient< TestRequestAction > ac_
Definition: exercise_simple_client.cpp:62
ros::shutdown
ROSCPP_DECL void shutdown()
SimpleClientFixture::SetUp
virtual void SetUp()
Definition: exercise_simple_client.cpp:56
TEST_F
TEST_F(SimpleClientFixture, just_succeed)
Definition: exercise_simple_client.cpp:66
actionlib::SimpleActionClient< TestRequestAction >
actionlib::SimpleClientGoalState::PENDING
@ PENDING
Definition: simple_client_goal_state.h:147
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
SimpleClientFixture::default_wait_
ros::Duration default_wait_
Definition: exercise_simple_client.cpp:63
SimpleClientFixture
Definition: exercise_simple_client.cpp:49
actionlib
Definition: action_definition.h:40
ros::spin
ROSCPP_DECL void spin()
simple_action_client.h
ros::Duration::sleep
bool sleep() const
ros::Duration
main
int main(int argc, char **argv)
Definition: exercise_simple_client.cpp:166
spinThread
void spinThread()
Definition: exercise_simple_client.cpp:160
ros::NodeHandle


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