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 &)
87 <<
"Expected [SUCCEEDED], but goal state is [" << state.
toString() <<
"]";
91 const TestResultConstPtr &)
95 <<
"Expected [SUCCEEDED], but terminal state is [" << terminal_state.
toString() <<
"]";
125 int main(
int argc,
char ** argv)
127 testing::InitGoogleTest(&argc, argv);
129 ros::init(argc, argv,
"simple_client_test");
133 int result = RUN_ALL_TESTS();
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
Blocks until this goal finishes.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string toString() const
Convert the state to a string. Useful when printing debugging information.
void easyDoneCallback(bool *called, const SimpleClientGoalState &state, const TestResultConstPtr &)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
Waits for the ActionServer to connect to this client.
SimpleClientGoalState getState() const
Get the state information for this goal.
void cancelGoalsAtAndBeforeTime(const ros::Time &time)
Cancel all goals that were stamped at and before the specified time.
A Simple client implementation of the ActionInterface which supports only one goal at a time...
TEST(SimpleClient, easy_tests)
int main(int argc, char **argv)
void easyOldDoneCallback(bool *called, const TerminalState &terminal_state, const TestResultConstPtr &)
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.
ROSCPP_DECL void shutdown()
std::string getText() const
void cancelAllGoals()
Cancel all goals currently running on the action server.
std::string toString() const