38 #include <actionlib/TestAction.h> 69 printf(
"Creating ActionServer [%s]\n", name.c_str());
79 gh.
setSucceeded(TestResult(),
"The ref server has succeeded");
83 gh.
setAborted(TestResult(),
"The ref server has aborted");
86 gh.
setRejected(TestResult(),
"The ref server has rejected");
98 int main(
int argc,
char ** argv)
int main(int argc, char **argv)
void goalCallback(GoalHandle gh)
ServerGoalHandle< TestAction > GoalHandle
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.
boost::shared_ptr< const Goal > getGoal() const
Accessor for the goal associated with the ServerGoalHandle.
void cancelCallback(GoalHandle gh)
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...
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
Set the status of the goal associated with the ServerGoalHandle to succeeded.
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.
RefServer(ros::NodeHandle &n, const std::string &name)
void start()
Explicitly start the action server, used it auto_start is set to false.
The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specif...