Go to the documentation of this file.
37 #include <gtest/gtest.h>
38 #include <actionlib/TestAction.h>
43 TEST(SimpleClient, easy_wait_test) {
56 "Expected [SUCCEEDED], but goal state is [" << client.
getState().
toString() <<
"]";
61 "Expected [PREEMPTED], but goal state is [" << client.
getState().
toString() <<
"]";
70 int main(
int argc,
char ** argv)
72 testing::InitGoogleTest(&argc, argv);
74 ros::init(argc, argv,
"simple_client_test");
78 int result = RUN_ALL_TESTS();
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
Waits for the ActionServer to connect to this client.
ROSCPP_DECL void shutdown()
A Simple client implementation of the ActionInterface which supports only one goal at a time.
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.
TEST(SimpleClient, easy_wait_test)
std::string toString() const
Convert the state to a string. Useful when printing debugging information.
SimpleClientGoalState getState() const
Get the state information for this goal.
actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55