• +4917626969472
  • info@ur-techpartner.de

ROS Basics (16/17) – Improved Action Client

Robot Operating System(ROS1/ROS2) ROS Programming

ROS Basics – Implement an improved Action Client

In previous blog, we have added new capabilities in Action Server. In this blog we will improve action client so that it can use newly added features of action server. For this, the action client will process feedback, cancel a goal, and trigger an abort feature that we have incorporated on action server side.

Creating an Improved Action Client File

We will implement a more sophisticated action client for the action “Timer.action”, that we are already using.

We will create new action client file in the package “ros_basics”.

Go to the package

Run the command

roscd ros_basics/src

Also run

ls

(To verify that the improved_action_client file is not already created.

Now create the file “improved_action_client.py”

For this run the command

touch improved_action_client.py

Run the command to give execute permission

chmod +x improved_action_client.py

Open the file using “gedit” command

Run the command

gedit improved_action_client.py

Copy and paste following code in it.

#! /usr/bin/env python
import rospy
import time
import actionlib
from ros_basics.msg import TimerAction, TimerGoal, TimerResult, TimerFeedback

def feedback_cb(feedback):
        print('[Feedback] Time elapsed: %f'%(feedback.time_elapsed.to_sec()))
        print('[Feedback] Time remaining: %f'%(feedback.time_remaining.to_sec()))

rospy.init_node('timer_action_client')
client = actionlib.SimpleActionClient('timer', TimerAction)
client.wait_for_server()

goal = TimerGoal()
goal.time_to_wait = rospy.Duration.from_sec(6.0)

# Uncomment this line to test server-side abort:
#goal.time_to_wait = rospy.Duration.from_sec(100.0)

client.send_goal(goal, feedback_cb=feedback_cb)

# Uncomment these lines to test goal preemption:
#time.sleep(3.0)
#client.cancel_goal()

client.wait_for_result()

print('[Result] State: %d'%(client.get_state()))
print('[Result] Status: %s'%(client.get_goal_status_text()))
print('[Result] Time elapsed: %f'%(client.get_result().time_elapsed.to_sec()))
print('[Result] Updates sent: %d'%(client.get_result().updates_sent))

All above executed commands are shown in figure below

The file “improved_action_client.py” will look like in figure below

Save and close the file

Explaining the Code in Python file “improved_action_client.py”

We will go through the key parts of the code. We may skip the lines that we have already explained.

def feedback_cb(feedback):
print(‘[Feedback] Time elapsed: %f’%(feedback.time_elapsed.to_sec()))
print(‘[Feedback] Time remaining: %f’%(feedback.time_remaining.to_sec()))

(In above lines, we defined a callback method named “ feedback_cb()”. This function will be invoked when the action client will receive feedback message from server. In this function, we are printing the contents of feedback).

client.send_goal(goal, feedback_cb=feedback_cb)

(In above line we are calling send_goal() method. We are registering callback by passing it as an argument feedback_cb, while sending the goal to the server).

client.wait_for_result()

(Above line will be executed when we will receive the result)

print(‘[Result] State: %d’%(client.get_state()))
print(‘[Result] Status: %s’%(client.get_goal_status_text()))
print(‘[Result] Time elapsed: %f’%(client.get_result().time_elapsed.to_sec()))
print(‘[Result] Updates sent: %d’%(client.get_result().updates_sent))

(Once we receive the result, the above lines will print the information received. The get_state() function returns the state of the goal. There are 10 possible states which are defined in actionlib_msgs/GoalStatus. Here, we will encounter three states which are PREEMPTED=2 , SUCCEEDED=3 , and ABORTED=4. We also print the status text which was sent by the server with the result).

You may check all states by running following command

Run in the terminal

rosmsg show actionlib_msgs/GoalStatus

You will see states as shown in figure below

Executing “improved_action_client.py” file

Now we will execute the file “improved_action_server.py” to view the functionality of the implemented improved action server and improved action client.

Open a terminal and run master

Run the command

roscore

Open another terminal and run the action server

Run the command

rosrun ros_basics improved_action_server.py

The terminal will look like in figure below

Observe Feedback and Result for Completed Timer

Now open a new terminal and run action client

Run the command

rosrun ros_basics improved_action_client.py

You will see the output after running action client. Feedback, status, status text and result are printed as shown in figure below.

Preempt the Goal

In action communication, ROS provides us a functionality that we may cancel goal at any time. This is useful if we receive some other priority task and we may not want to continue current action.

open the file improved_action_client.py

and uncomment following two lines

time.sleep(3.0)
client.cancel_goal()

#(This line will request the server to preempt the goal by calling function cancel_goal())

Run action client again

Run the command

rosrun ros_basics improved_action_client.py

You will see that after almost 3 seconds, the timer is preempted as show in figure below

Trigger an Abort on Server-side

Now we will change the time_to_wait duration more than 60 seconds, so that it can trigger an abort on server side.

Comment the following line

#goal.time_to_wait = rospy.Duration.from_sec(6.0)

(We can directly change value in above line, however we added additional line below to keep both lines.)

Also comment the two lines (that we uncommented before)

#time.sleep(3.0)
#client.cancel_goal()

Now uncomment the following line

goal.time_to_wait = rospy.Duration.from_sec(100.0)

Save the file, and run the action client again

Run the command

rosrun ros_basics improved_action_client.py

You will see that we did not receive any feedback, instead the Timer is aborted. You may cross check that this (long time duration checking) functionality was implemented at top of the action server program by opening improved_action_server.py file

At this stage you are almost familiar with all the features that an action can perform. Later you will learn more efficient use of action while working in ROS.

We have completed the series of ROS Basics Blogs. In this series we discussed three essential communication mechanism of ROS which are Topic, Service, and Action. In these blogs we have practically learned various concepts including Topics, Publisher, Subscriber, Message, Service, Service Server, Service Client, Action, Action Server, Action Client and customized our own Message, Service, and Action. We also discussed how to create and compile the packages. Everything that we have covered in these blogs is implemented using Python. However, you can implement same concepts using c++. Next we will discuss other aspects of robots and will move to advance concepts.

No comments