35 from actionlib.msg
import TestAction, TestFeedback
41 action_spec = TestAction
42 SimpleActionServer.__init__(
45 rospy.loginfo(
"Creating SimpleActionServer [%s]\n", name)
48 rospy.loginfo(
"Got goal %d", int(goal.goal))
52 self.
set_aborted(
None,
"The ref server has aborted")
54 self.
set_aborted(
None,
"The simple action server can't reject goals")
56 self.
set_aborted(
None,
"Simple server can't save goals")
58 self.
set_aborted(
None,
"Simple server can't save goals")
60 self.
set_aborted(
None,
"Simple server can't save goals")
62 self.
set_aborted(
None,
"Simple server can't save goals")
64 self.
set_aborted(
None,
"Simple server can't save goals")
67 rospy.loginfo(
"Sending feedback")
75 if __name__ ==
"__main__":
76 rospy.init_node(
"ref_simple_server")
def goal_callback(self, goal)
def set_aborted(self, result=None, text="")
Sets the status of the active goal to aborted.
def publish_feedback(self, feedback)
Publishes feedback for a given goal.
def set_succeeded(self, result=None, text="")
Sets the status of the active goal to succeeded.
def start(self)
Explicitly start the action server, used it auto_start is set to false.
The SimpleActionServer implements a singe goal policy on top of the ActionServer class.