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

Revision history [back]

I found the following way using asynchronous callbacks modified from the docs:

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node

from action_msgs.msg import GoalStatus
from action_tutorials_interfaces.action import Fibonacci


class FibonacciActionClient(Node):

    def __init__(self):
        super().__init__('fibonacci_action_client')
        self._action_client = ActionClient(self, Fibonacci, 'fibonacci')
        self.status = GoalStatus.STATUS_EXECUTING

    def send_goal(self, order):
        self.status = GoalStatus.STATUS_EXECUTING
        goal_msg = Fibonacci.Goal()
        goal_msg.order = order

        self._action_client.wait_for_server()

        self._send_goal_future = self._action_client.send_goal_async(goal_msg, feedback_callback=self.feedback_callback)

        self._send_goal_future.add_done_callback(self.goal_response_callback)

    def goal_response_callback(self, future):
        goal_handle = future.result()
        if not goal_handle.accepted:
            self.get_logger().info('Goal rejected :(')
            return

        self.get_logger().info('Goal accepted :)')

        self._get_result_future = goal_handle.get_result_async()
        self._get_result_future.add_done_callback(self.get_result_callback)

    def get_result_callback(self, future):
        result = future.result().result
        self.get_logger().info('Result: {0}'.format(result.sequence))
        self.status = GoalStatus.STATUS_SUCCEEDED

    def feedback_callback(self, feedback_msg):
        feedback = feedback_msg.feedback
        self.get_logger().info('Received feedback: {0}'.format(feedback.partial_sequence))


def main(args=None):
    rclpy.init(args=args)
    action_client = FibonacciActionClient()
    action_client.send_goal(10)

    while action_client.status != GoalStatus.STATUS_SUCCEEDED:
        rclpy.spin_once(action_client)

    action_client.get_logger().info('All done!')
    action_client.destroy_node()

if __name__ == '__main__':
    main()

You can also use this method to make successive calls to action_client.send_goal() and it will wait until each goal is done before the next goal is called. You just have to have the while loop inside the for loop, i.e:

def main(args=None):
    rclpy.init(args=args)
    action_client = FibonacciActionClient()

    goals = [10, 11, 12, 13, 14, 15]

    for goal in goals:

        action_client.send_goal(10)

        while action_client.status != GoalStatus.STATUS_SUCCEEDED:
            rclpy.spin_once(action_client)

    action_client.get_logger().info('All done!')
    action_client.destroy_node()

I found the following way using asynchronous callbacks modified from the docs:

import rclpy
from rclpy.action import ActionClient
from rclpy.node import Node

from action_msgs.msg import GoalStatus
from action_tutorials_interfaces.action import Fibonacci


class FibonacciActionClient(Node):

    def __init__(self):
        super().__init__('fibonacci_action_client')
        self._action_client = ActionClient(self, Fibonacci, 'fibonacci')
        self.status = GoalStatus.STATUS_EXECUTING

    def send_goal(self, order):
        self.status = GoalStatus.STATUS_EXECUTING
        goal_msg = Fibonacci.Goal()
        goal_msg.order = order

        self._action_client.wait_for_server()

        self._send_goal_future = self._action_client.send_goal_async(goal_msg, feedback_callback=self.feedback_callback)

        self._send_goal_future.add_done_callback(self.goal_response_callback)

    def goal_response_callback(self, future):
        goal_handle = future.result()
        if not goal_handle.accepted:
            self.get_logger().info('Goal rejected :(')
            return

        self.get_logger().info('Goal accepted :)')

        self._get_result_future = goal_handle.get_result_async()
        self._get_result_future.add_done_callback(self.get_result_callback)

    def get_result_callback(self, future):
        result = future.result().result
        self.get_logger().info('Result: {0}'.format(result.sequence))
        self.status = GoalStatus.STATUS_SUCCEEDED

    def feedback_callback(self, feedback_msg):
        feedback = feedback_msg.feedback
        self.get_logger().info('Received feedback: {0}'.format(feedback.partial_sequence))


def main(args=None):
    rclpy.init(args=args)
    action_client = FibonacciActionClient()
    action_client.send_goal(10)

    while action_client.status != GoalStatus.STATUS_SUCCEEDED:
        rclpy.spin_once(action_client)

    action_client.get_logger().info('All done!')
    action_client.destroy_node()

if __name__ == '__main__':
    main()

You can also use this method to make successive calls to action_client.send_goal() and it will wait until each goal is done before the next goal is called. You just have to have the while loop inside the for loop, i.e:

def main(args=None):
    rclpy.init(args=args)
    action_client = FibonacciActionClient()

    goals = [10, 11, 12, 13, 14, 15]

    for goal in goals:

        action_client.send_goal(10)
action_client.send_goal(goal)

        while action_client.status != GoalStatus.STATUS_SUCCEEDED:
            rclpy.spin_once(action_client)

    action_client.get_logger().info('All done!')
    action_client.destroy_node()