38 #include <actionlib/TestAction.h> 41 #include <gtest/gtest.h> 92 gh.
setSucceeded(TestResult(),
"The ref server has succeeded");
96 gh.
setAborted(TestResult(),
"The ref server has aborted");
99 gh.
setRejected(TestResult(),
"The ref server has rejected");
113 TEST(ServerGoalHandleDestruction, destruction_test) {
114 boost::thread spin_thread(&
spinner);
133 int main(
int argc,
char ** argv)
135 testing::InitGoogleTest(&argc, argv);
139 return RUN_ALL_TESTS();
boost::shared_ptr< const Goal > getGoal() const
Accessor for the goal associated with the ServerGoalHandle.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setRejected(const Result &result=Result(), const std::string &text=std::string(""))
Set the status of the goal associated with the ServerGoalHandle to rejected.
~ServerGoalHandleDestructionTester()
void goalCallback(GoalHandle gh)
ServerGoalHandle< TestAction > GoalHandle
ActionServer< TestAction > * as_
void setAccepted(const std::string &text=std::string(""))
Accept the goal referenced by the goal handle. This will transition to the ACTIVE state or the PREEMP...
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
Waits for the ActionServer to connect to this client.
int main(int argc, char **argv)
void registerGoalCallback(boost::function< void(GoalHandle)> cb)
Register a callback to be invoked when a new goal is received, this will replace any previously regis...
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
Set the status of the goal associated with the ServerGoalHandle to succeeded.
A Simple client implementation of the ActionInterface which supports only one goal at a time...
Encapsulates a state machine for a given goal that the user can trigger transitions on...
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
Set the status of the goal associated with the ServerGoalHandle to aborted.
void start()
Explicitly start the action server, used it auto_start is set to false.
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.
ServerGoalHandleDestructionTester()
#define ROS_ERROR_NAMED(name,...)
ROSCPP_DECL void shutdown()
TEST(ServerGoalHandleDestruction, destruction_test)