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

How do I create a callback-based actionlib client in python?

asked 2018-05-23 15:05:00 -0500

dsoike gravatar image

The actionlib tutorial on Writing a Callback Based Simple Action Client shows how to do it in C++, but there isn't a tutorial for Python.

The Writing a Simple Action Client (Python) tutorial only demonstrates synchronous behavior with client.wait_for_server(), which does not allow for actionlib feedback.

A simple example would be much appreciated.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2018-05-23 16:14:07 -0500

NickKnack15 gravatar image

updated 2018-05-23 16:43:18 -0500

Hello there!

I think I have something just for you. I created a simple demo on how to create a call-back based actionlib implementation for Python 2.7. You can find the demo here python-actionlib-demo!

When you build the package and run the nodes, there are 2 actions that can be triggered and cancelled independently of each other. This shows how easy it is to leverage the asynchronous capability of actionlib without dealing with the threading overhead in Python 2.7!

Hope this helps!

edit flag offensive delete link more

Comments

1

Can you please update your answer with a minimum working example? This way it'll be self-contained.

jayess gravatar image jayess  ( 2018-05-23 18:33:24 -0500 )edit
4

answered 2020-01-20 15:59:18 -0500

peterb gravatar image

updated 2020-01-20 16:00:58 -0500

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

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 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
edit flag offensive delete link more

Question Tools

Stats

Asked: 2018-05-23 15:05:00 -0500

Seen: 3,650 times

Last updated: Jan 20 '20