simple_client_wait_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_wait_test) {
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;
52 
53  goal.goal = 1;
54  state = client.sendGoalAndWait(goal, ros::Duration(10, 0), ros::Duration(10, 0));
55  EXPECT_TRUE(state == SimpleClientGoalState::SUCCEEDED) <<
56  "Expected [SUCCEEDED], but goal state is [" << client.getState().toString() << "]";
57 
58  goal.goal = 4;
59  state = client.sendGoalAndWait(goal, ros::Duration(2, 0), ros::Duration(1, 0));
60  EXPECT_TRUE(state == SimpleClientGoalState::PREEMPTED) <<
61  "Expected [PREEMPTED], but goal state is [" << client.getState().toString() << "]";
62 }
63 
64 void spinThread()
65 {
66  ros::NodeHandle nh;
67  ros::spin();
68 }
69 
70 int main(int argc, char ** argv)
71 {
72  testing::InitGoogleTest(&argc, argv);
73 
74  ros::init(argc, argv, "simple_client_test");
75 
76  boost::thread spin_thread(&spinThread);
77 
78  int result = RUN_ALL_TESTS();
79 
80  ros::shutdown();
81 
82  spin_thread.join();
83 
84  return result;
85 }
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
main
int main(int argc, char **argv)
Definition: simple_client_wait_test.cpp:70
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::SimpleClientGoalState::LOST
@ LOST
Definition: simple_client_goal_state.h:154
actionlib::SimpleActionClient
A Simple client implementation of the ActionInterface which supports only one goal at a time.
Definition: simple_action_client.h:72
actionlib::SimpleActionClient::sendGoalAndWait
SimpleClientGoalState sendGoalAndWait(const Goal &goal, const ros::Duration &execute_timeout=ros::Duration(0, 0), const ros::Duration &preempt_timeout=ros::Duration(0, 0))
Sends a goal to the ActionServer, and waits until the goal completes or a timeout is exceeded.
Definition: simple_action_client.h:610
TEST
TEST(SimpleClient, easy_wait_test)
Definition: simple_client_wait_test.cpp:43
spinThread
void spinThread()
Definition: simple_client_wait_test.cpp:64
actionlib::SimpleClientGoalState::SUCCEEDED
@ SUCCEEDED
Definition: simple_client_goal_state.h:153
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()
simple_action_client.h
actionlib::SimpleActionClient::getState
SimpleClientGoalState getState() const
Get the state information for this goal.
Definition: simple_action_client.h:338
actionlib::SimpleClientGoalState::PREEMPTED
@ PREEMPTED
Definition: simple_client_goal_state.h:151
ros::Duration
ros::NodeHandle


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