Note: This tutorial assumes that you have completed the previous tutorials: Bringing up Care-O-bot, Running a simple grasp script.
(!) 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.

Preparing a new script (python)

Description: This tutorial shows how to write a simple script for grasping and handing over an object using cob_script_server.

Tutorial Level: BEGINNER

Next Tutorial: Using the move command (python) Using other commands (python)

Including cob_script_server

cob_script_server provides basic functions to make simple movements with Care-O-bot’s arms, grippers, torso and base. cob_script_server provides a Python interface which can be included in any other script. To do so, prepare the following script structure:

   1 #!/usr/bin/python
   2 
   3 import roslib
   4 roslib.load_manifest('cob_script_server')
   5 import rospy
   6 
   7 from simple_script_server import script
   8 
   9 class MyScript(script):
  10     def Initialize(self):
  11         rospy.loginfo("Initializing all components...")
  12 
  13     def Run(self):
  14         rospy.loginfo("Running script...")
  15 
  16 if __name__ == "__main__":
  17     SCRIPT = MyScript()
  18     SCRIPT.Start()

As you can see you have declared a new class MyScript with two functions Initialize and Run. The class MyScript inherits from the script class which provides the functionalities of the cob_script_server as a python API. The Initialze-function will later be used to send an init-command to all components and move them to initial positions so that the script can be started. The Run-function will later contain the main script.

Save your file in a ROS package. For testing you should save the file as my_script.py in the folder <cob_script_server_tutorial>/scripts/.

Initializing Components

If you want to run your script on a real robot all components need to be initialized before they can be moved. For doing this, the routine Init("<component_name>") is provided. In order to initialize all components, add an Init-command for each component to your Initialize-function:

   1     def Initialize(self):
   2         rospy.loginfo("Initializing all components...")
   3         self.sss.init("base")
   4         self.sss.init("torso")
   5         self.sss.init("arm_left")
   6         self.sss.init("arm_right")
   7         self.sss.init("gripper_left")
   8         self.sss.init("gripper_right")

For simulation this step is not neccessary.

Furthermore before the script can be started all components should move to their initial positions:

   1     def Initialize(self):
   2         rospy.loginfo("Initializing all components...")
   3         self.sss.init("base")
   4         self.sss.init("torso")
   5         self.sss.init("arm_left")
   6         self.sss.init("arm_right")
   7         self.sss.init("gripper_left")
   8         self.sss.init("gripper_right")
   9 
  10         # move to initial positions
  11         self.sss.move("torso","home")
  12         self.sss.move("arm_left","side")
  13         self.sss.move("arm_right","side")
  14         self.sss.move("gripper_left","close")
  15         self.sss.move("gripper_right","close")

Running your script for the first time

Although the script does nothing really useful yet, it is a good idea to run it now for the first time. Doing so allows you to check if everything is set up correctly and if all packages you need are there. To run your script you have to

  1. Make your script executable by typing in a shell
     chmod 755 my_script.py
  2. Bringup a robot. For starting Care-O-bot in simulation type
     export ROBOT=cob4-3
     roslaunch cob_bringup_sim robot.launch

    For detailed instructions about this package have a look at cob_bringup_sim.

  3. Start cob_script_server by typing

     roslaunch cob_script_server_tutorial script_server_tutorial.launch

    For detailed instructions about this package have a look at cob_script_server.

    Note that you have to start cob_script_server although you include it directly in your script and do not want to send messages to it. This is necessary because the package also sets up all parameters, e.g. joint angles for certain positions.

  4. Start your script. If you have saved your script as my_script.py in <cob_script_server_tutorial>/scripts/ you need to issue the command

     rosrun cob_script_server_tutorial my_script.py

If you have done everything right, you will see some messages saying that Care-O-bot's components are initializing (For simulation this will fail, but you don't have to care about this). As step 1-3 only have to be done once you can now start your script anytime you like by repeating step 4.

Wiki: cob_script_server/Tutorials/Preparing a new script (python) (last edited 2019-09-24 10:40:58 by HannesBachter)