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 the Action Client
Description: Shows how to use opencupboard_actionTutorial Level: BEGINNER
Next Tutorial: Running the Action Client
Compiling opencupboard stack
If you have not downloaded the opencupboard stack, please do so by following:
svn co `roslocate svn opencupboard`
After you do that, make sure stack is compiled on your local machine by:
roscd opencupboard rosmake
The opencupboard stack relies on implementation of pr_tabletop_manipulation, move_arm service, and ee_cart_imped force controller. For the specifics of these packages, please see tutorials for tabletop_manipulation, tutorials for move_arm, and tutorials for ee_cart_imped.
The Code
First, create a package for this tutorial. Open a new shell, navigate to a directory on your ROS_PACKAGE_PATH in which you wish to do the tutorial and type
roscreate-pkg opencupboard_tutorial opencupboard_action opencupboard_msgs opencupboard_launch actionlib
Within that package, create the scripts/action_client.py file and paste the following inside it:
1 #!/usr/bin/env python
2 import roslib; roslib.load_manifest('opencupboard_action')
3 import rospy
4 import actionlib
5 import opencupboard_msgs.msg
6
7 def main():
8 '''
9 Runs the openCupboard action.
10 '''
11 open_cupboard_client = actionlib.SimpleActionClient( 'open_cupboard_action',opencupboard_msgs.msg.OpenCupboardAction)
12
13 print "waiting for server"
14 open_cupboard_client.wait_for_server()
15
16 goal = opencupboard_msgs.msg.OpenCupboardGoal()
17 goal.open_cupboard = True
18 print "sending goal"
19 open_cupboard_client.send_goal(goal)
20
21 print "waiting for result"
22 open_cupboard_client.wait_for_result()
23
24 print "RESULT:",open_cupboard_client.get_result()
25
26 if __name__ == '__main__':
27 rospy.init_node('test_open_cupboard_action')
28 main()
Examining the Code
These lines import the action library and the opencupboard_action's messages.
11 open_cupboard_client = actionlib.SimpleActionClient( 'open_cupboard_action',opencupboard_msgs.msg.OpenCupboardAction)
This is the instantiation of the client. You must pass it the name of the action and the action messages.
14 open_cupboard_client.wait_for_server()
Waits until the action server is running.
Creates a goal and sets open_cupboard to True. This just indicates that you want to execute the action.
Sends the goal and waits for the result
Running the Code
Change your file to be executable:
roscd opencupboard_tutorial/scripts chmod +x action_client.py
Now we are ready to run the code.