37 #ifndef ACTIONLIB__SERVER__SERVICE_SERVER_IMP_H_ 38 #define ACTIONLIB__SERVER__SERVICE_SERVER_IMP_H_ 45 template<
class ActionSpec>
47 boost::function<
bool(
const typename ActionSpec::_action_goal_type::_goal_type &,
48 typename ActionSpec::_action_result_type::_result_type & result)> service_cb)
55 template<
class ActionSpec>
57 boost::function<
bool(
const Goal &, Result & result)> service_cb)
58 : service_cb_(service_cb)
65 template<
class ActionSpec>
68 goal.
setAccepted(
"This goal has been accepted by the service server");
73 goal.
setSucceeded(r,
"The service server successfully processed the request");
75 goal.
setAborted(r,
"The service server failed to process the request");
80 #endif // ACTIONLIB__SERVER__SERVICE_SERVER_IMP_H_
void goalCB(GoalHandle g)
boost::shared_ptr< ActionServer< ActionSpec > > as_
ServiceServer advertiseService(ros::NodeHandle n, std::string name, boost::function< bool(const typename ActionSpec::_action_goal_type::_goal_type &, typename ActionSpec::_action_result_type::_result_type &result)> service_cb)
ServiceServerImpT(ros::NodeHandle n, std::string name, boost::function< bool(const Goal &, Result &result)> service_cb)
boost::shared_ptr< const Goal > getGoal() const
Accessor for the goal associated with the ServerGoalHandle.
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.
The ActionServer is a helpful tool for managing goal requests to a node. It allows the user to specif...
boost::function< bool(const Goal &, Result &result)> service_cb_