(!) 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.

Python tutorial to interact with open_loop_object_manipulation_actionserver

Description: This tutorial will show you how to interact with the drive_to_action_server in Python

Tutorial Level: INTERMEDIATE

Introduction

This tutorial shows you how you can use the rl_2dnav to navigate between the 5 possible robot locations in the remote lab.

Writing The Code

This piece shows the whole code. Then below we'll slowly break things down bit by bit.

   1 import roslib; roslib.load_manifest('aaai_lfd_demo_executive')
   2 import rospy
   3 import actionlib
   4 import math
   5 import copy
   6 import geometry_msgs.msg 
   7 import rl_2dnav.msg as navigation_action_msg
   8 
   9 class AAAILfDDriver:
  10 
  11  def __init__(self):
  12     self.navigation_server = actionlib.SimpleActionClient('drive_to_action_server', navigation_action_msg.DriveToAction)
  13     rospy.loginfo('Waiting for navigation server')
  14     self.navigation_server.wait_for_server()
  15  
  16 def navigate(self, location):
  17         print "navigating location %s", (location)
  18         goal = navigation_action_msg.DriveToGoal()  
  19         goal.pose = location
  20     
  21         rospy.loginfo('Sending goal')
  22         self.navigation_server.send_goal(goal)
  23         rospy.loginfo('Waiting for results')
  24         self.navigation_server.wait_for_result()
  25  
  26 
  27   
  28 if __name__ == '__main__':
  29     try:
  30         # Initializes a rospy node so that the SimpleActionClient can
  31         # publish and subscribe over ROS.
  32         rospy.init_node('aaai_lfd_demo_driver')
  33         driver = AAAILfDDriver()
  34         driver.navigate(3)
  35         
  36     except rospy.ROSInterruptException:
  37         print "program interrupted before completion"

In this example, we create a class to drive to any of the prerecorded positions. In particular this code will result in the robot driving to the third position.

Initialization

   1 import roslib; roslib.load_manifest('aaai_lfd_demo_executive')
   2 import rospy
   3 import actionlib
   4 import math
   5 import copy
   6 import geometry_msgs.msg 
   7 import rl_2dnav.msg as navigation_action_msg

This portion of the code includes the files necessary to write the code

Class Initialization

   1 class AAAILfDDriver:
   2 
   3  def __init__(self):
   4     self.navigation_server = actionlib.SimpleActionClient('drive_to_action_server', navigation_action_msg.DriveToAction)
   5     rospy.loginfo('Waiting for navigation server')
   6     self.navigation_server.wait_for_server()

This declares a class AAAILfDDriver and the init function. Within the init function we can break things down further:

self.navigation_server = actionlib.SimpleActionClient('drive_to_action_server', navigation_action_msg.DriveToAction)

creates self.navigation_server, an action client to the drive_to_action_server.

    rospy.loginfo('Waiting for navigation server')
    self.navigation_server.wait_for_server()

These lines wait for the action server to respond that it is running.

Using the Action Server

   1 def navigate(self, location):
   2         print "navigating location %s", (location)
   3         goal = navigation_action_msg.DriveToGoal()  
   4         goal.pose = location
   5     
   6         rospy.loginfo('Sending goal')
   7         self.navigation_server.send_goal(goal)
   8         rospy.loginfo('Waiting for results')
   9         self.navigation_server.wait_for_result()

def navigate(self, location):

Defines a function manipulate that takes three arguments: the desired object, the action, and which arm should be used

goal = navigation_action_msg.DriveToGoal()  
goal.pose = location

These lines create a goal for the drive_to_action_server

self.navigation_server.send_goal(goal)

This line sends the goal to the action server

self.navigation_server.wait_for_result()

This line waits for the result

Move to position 3

This code shows the main function which uses the class we created in the previous sections.

   1 if __name__ == '__main__':
   2     try:
   3         # Initializes a rospy node so that the SimpleActionClient can
   4         # publish and subscribe over ROS.
   5         rospy.init_node('aaai_lfd_demo_driver')
   6         driver = AAAILfDDriver()
   7         driver.navigate(3)
   8         
   9     except rospy.ROSInterruptException:
  10         print "program interrupted before completion"

rospy.init_node('aaai_lfd_demo_driver')

Initializes this rosnode

driver = AAAILfDDriver()

Creates a new instance of the class we created

driver.navigate(3)

Asks the class drive to the third position.

Wiki: rl_2dnav/Tutorials/Using rl_2dnav action server (last edited 2011-06-08 23:59:51 by SarahOsentoski)