ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

However there is nothing wrong with this answer I put here a minimal code example:

client.send_goal(CounterGoal(10),
                active_cb=callback_active,
                feedback_cb=callback_feedback,
                done_cb=callback_done)

The three callbacks are for when action server starts to process the goal, for the feedback and for the result.

Here is the nearly full client code:

#! /usr/bin/env python

import rospy
import actionlib
from package_where CounterAction_is_declared.msg import CounterAction, CounterGoal, CounterResult

def counter_client():
    client = actionlib.SimpleActionClient('counter_as', CounterAction)
    rospy.loginfo("Waiting for action server to come up...")
    client.wait_for_server()

    client.send_goal(CounterGoal(10),
                    active_cb=callback_active,
                    feedback_cb=callback_feedback,
                    done_cb=callback_done)

    rospy.loginfo("Goal has been sent to the action server.")

def callback_active():
    rospy.loginfo("Action server is processing the goal")

def callback_done(state, result):
    rospy.loginfo("Action server is done. State: %s, result: %s" % (str(state), str(result)))

def callback_feedback(feedback):
    rospy.loginfo("Feedback:%s" % str(feedback))

if __name__ == '__main__':
    try:
        rospy.init_node('counter_ac')
        counter_client()
        rospy.spin()
    except rospy.ROSInterruptException:
        rospy.loginfo("program interrupted before completion")

The action server code:

#! /usr/bin/env python

import rospy
import actionlib
from package_where CounterAction_is_declared.msg import CounterAction, CounterFeedback, CounterResult

class CounterActionClass(object):
    def __init__(self):
        self._as = actionlib.SimpleActionServer(
            rospy.get_name(),
            CounterAction,
            execute_cb=self.execute_cb,
            auto_start = False)

        self._as.start()
        rospy.loginfo("Action server %s started." % rospy.get_name())

    def execute_cb(self, goal):
        rospy.loginfo('%s action server is counting up to  %i' % (rospy.get_name(), goal.num_counts))
        success = True
        rate = rospy.Rate(1)

        for i in range(0, goal.num_counts):
            if self._as.is_preempt_requested():
                rospy.loginfo('%s: Preempted' % rospy.get_name())
                self._as.set_preempted()
                success = False
                break

            self._as.publish_feedback(CounterFeedback(i))
            rate.sleep()

        if success:
            rospy.loginfo('%s: Succeeded' % rospy.get_name())
            self._as.set_succeeded(CounterResult("Done"))

if __name__ == '__main__':
    rospy.init_node('counter_as')
    server = CounterActionClass()
    rospy.spin()

And the Counter.action file:

uint32 num_counts
---
string result_message
---
uint32 counts_elapsed

However there is nothing wrong with this answer I put here a minimal code example:

client.send_goal(CounterGoal(10),
client.send_goal(goal,
                active_cb=callback_active,
                feedback_cb=callback_feedback,
                done_cb=callback_done)

The three callbacks are for when action server starts to process the goal, for the feedback and for the result.

Here is the nearly full client code:

#! /usr/bin/env python

import rospy
import actionlib
from package_where CounterAction_is_declared.msg package_where_CounterAction_is_declared.msg import CounterAction, CounterGoal, CounterResult

def counter_client():
    client = actionlib.SimpleActionClient('counter_as', CounterAction)
    rospy.loginfo("Waiting for action server to come up...")
    client.wait_for_server()

    client.send_goal(CounterGoal(10),
                    active_cb=callback_active,
                    feedback_cb=callback_feedback,
                    done_cb=callback_done)

    rospy.loginfo("Goal has been sent to the action server.")

def callback_active():
    rospy.loginfo("Action server is processing the goal")

def callback_done(state, result):
    rospy.loginfo("Action server is done. State: %s, result: %s" % (str(state), str(result)))

def callback_feedback(feedback):
    rospy.loginfo("Feedback:%s" % str(feedback))

if __name__ == '__main__':
    try:
        rospy.init_node('counter_ac')
        counter_client()
        rospy.spin()
    except rospy.ROSInterruptException:
        rospy.loginfo("program interrupted before completion")

The action server code:

#! /usr/bin/env python

import rospy
import actionlib
from package_where CounterAction_is_declared.msg package_where_CounterAction_is_declared.msg import CounterAction, CounterFeedback, CounterResult

class CounterActionClass(object):
    def __init__(self):
        self._as = actionlib.SimpleActionServer(
            rospy.get_name(),
            CounterAction,
            execute_cb=self.execute_cb,
            auto_start = False)

        self._as.start()
        rospy.loginfo("Action server %s started." % rospy.get_name())

    def execute_cb(self, goal):
        rospy.loginfo('%s action server is counting up to  %i' % (rospy.get_name(), goal.num_counts))
        success = True
        rate = rospy.Rate(1)

        for i in range(0, goal.num_counts):
            if self._as.is_preempt_requested():
                rospy.loginfo('%s: Preempted' % rospy.get_name())
                self._as.set_preempted()
                success = False
                break

            self._as.publish_feedback(CounterFeedback(i))
            rate.sleep()

        if success:
            rospy.loginfo('%s: Succeeded' % rospy.get_name())
            self._as.set_succeeded(CounterResult("Done"))

if __name__ == '__main__':
    rospy.init_node('counter_as')
    server = CounterActionClass()
    rospy.spin()

And the Counter.action file:

uint32 num_counts
---
string result_message
---
uint32 counts_elapsed