(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Writing a Simple Action Client (Python)

Description: This tutorial covers using the action_client library to create a Fibonacci simple action client in Python.

Tutorial Level: BEGINNER

The code and examples used in this tutorial can be found in the actionlib_tutorials package. You may want to read about the actionlib package before starting this tutorial.

The Code

The following code can be found in actionlib_tutorials repository, and implements a simple python action client for the fibonacci action.

   1 #! /usr/bin/env python
   2 
   3 import rospy
   4 from __future__ import print_function
   5 
   6 # Brings in the SimpleActionClient
   7 import actionlib
   8 
   9 # Brings in the messages used by the fibonacci action, including the
  10 # goal message and the result message.
  11 import actionlib_tutorials.msg
  12 
  13 def fibonacci_client():
  14     # Creates the SimpleActionClient, passing the type of the action
  15     # (FibonacciAction) to the constructor.
  16     client = actionlib.SimpleActionClient('fibonacci', actionlib_tutorials.msg.FibonacciAction)
  17 
  18     # Waits until the action server has started up and started
  19     # listening for goals.
  20     client.wait_for_server()
  21 
  22     # Creates a goal to send to the action server.
  23     goal = actionlib_tutorials.msg.FibonacciGoal(order=20)
  24 
  25     # Sends the goal to the action server.
  26     client.send_goal(goal)
  27 
  28     # Waits for the server to finish performing the action.
  29     client.wait_for_result()
  30 
  31     # Prints out the result of executing the action
  32     return client.get_result()  # A FibonacciResult
  33 
  34 if __name__ == '__main__':
  35     try:
  36         # Initializes a rospy node so that the SimpleActionClient can
  37         # publish and subscribe over ROS.
  38         rospy.init_node('fibonacci_client_py')
  39         result = fibonacci_client()
  40         print("Result:", ', '.join([str(n) for n in result.sequence]))
  41     except rospy.ROSInterruptException:
  42         print("program interrupted before completion", file=sys.stderr)

The Code, explained

  11 import actionlib_tutorials.msg

The action specification generates several messages for sending goals, receiving feedback, etc... This line imports the generated messages.

  16     client = actionlib.SimpleActionClient('fibonacci', actionlib_tutorials.msg.FibonacciAction)

The action client and server communicate over a set of topics, described in the actionlib protocol. The action name describes the namespace containing these topics, and the action specification message describes what messages should be passed along these topics.

  20     client.wait_for_server()

Sending goals before the action server comes up would be useless. This line waits until we are connected to the action server.

  22     # Creates a goal to send to the action server.
  23     goal = actionlib_tutorials.msg.FibonacciGoal(order=20)
  24 
  25     # Sends the goal to the action server.
  26     client.send_goal(goal)

Creates a goal and sends it to the action server.

  28     # Waits for the server to finish performing the action.
  29     client.wait_for_result()
  30 
  31     # Prints out the result of executing the action
  32     return client.get_result()  # A FibonacciResult

The action server will process the goal and eventually terminate. We want the result from the termination, but we wait until the server has finished with the goal.

Running the Client

Before running the client, we assume roscore ans Action server are already running from previous page.

Start the client. It will start up, send a goal to the server, wait for the goal to complete, and then exit.

$ rosrun actionlib_tutorials fibonacci_client.py

Wiki: actionlib_tutorials/Tutorials/Writing a Simple Action Client (Python) (last edited 2023-03-08 08:40:12 by Hirotaka Yamada)