Go to the documentation of this file.
37 #include <gtest/gtest.h>
38 #include <actionlib/TestAction.h>
43 TEST(SimpleClient, easy_tests) {
58 ASSERT_TRUE(finished);
60 <<
"Expected [SUCCEEDED], but goal state is [" << client.
getState().
toString() <<
"]";
63 EXPECT_TRUE(client.
getState().
getText() ==
"The ref server has succeeded");
68 ASSERT_TRUE(finished);
70 <<
"Expected [ABORTED], but goal state is [" << client.
getState().
toString() <<
"]";
73 EXPECT_TRUE(client.
getState().
getText() ==
"The ref server has aborted");
83 const TestResultConstPtr &)
86 <<
"Expected [SUCCEEDED], but getState() returned [" << ac->
getState().
toString() <<
"]";
88 <<
"Expected [SUCCEEDED], but goal state is [" << state.
toString() <<
"]";
93 TEST(SimpleClient, easy_callback)
112 ASSERT_TRUE(finished);
113 EXPECT_TRUE(called) <<
"easyDoneCallback() was never called" ;
122 int main(
int argc,
char ** argv)
124 testing::InitGoogleTest(&argc, argv);
126 ros::init(argc, argv,
"simple_client_test");
130 int result = RUN_ALL_TESTS();
int main(int argc, char **argv)
boost::function< void(const SimpleClientGoalState &state, const ResultConstPtr &result)> SimpleDoneCallback
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
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.
std::string getText() const
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.
void cancelGoalsAtAndBeforeTime(const ros::Time &time)
Cancel all goals that were stamped at and before the specified time.
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
Blocks until this goal finishes.
std::string toString() const
Convert the state to a string. Useful when printing debugging information.
void easyDoneCallback(bool *called, SimpleActionClient< TestAction > *ac, const SimpleClientGoalState &state, const TestResultConstPtr &)
SimpleClientGoalState getState() const
Get the state information for this goal.
void cancelAllGoals()
Cancel all goals currently running on the action server.
TEST(SimpleClient, easy_tests)
actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55