Note: This tutorial assumes that you have completed the previous tutorials: Getting Started.
(!) 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.

Multiple Tasks

Description: This tutorial shows you how to run multiple tasks with teer.

Tutorial Level: BEGINNER

Next Tutorial: Wait on Multiple Tasks

How multitasking works in teer

Teer provides cooperative multitasking, that is, tasks run until they explicitly give hand back to the scheduler using the yield keyword. Because task switching is explicit, there is no synchronisation issues. As rospy is heavily multi-threaded, the scheduler protects access to tasks using a threading.Condition. The scheduler runs tasks using a round-robin policy.

An example with multiple tasks

The following example is the simplified ROS version of an example from teer's distribution:

   1 #!/usr/bin/env python
   2 import roslib; roslib.load_manifest('teer_tutorials')
   3 import rospy
   4 from teer_ros import *
   5 
   6 def tick():
   7     rate = sched.create_rate(10)
   8     while True:
   9         print '.',
  10         sys.stdout.flush()
  11         yield Sleep(rate)
  12 
  13 def world():
  14     print 'World'
  15     yield WaitDuration(1)
  16     print 'Bye'
  17 
  18 def hello():
  19     tick_tid = sched.new_task(tick())
  20     print 'Hello'
  21     world_tid = sched.new_task(world())
  22     print 'hi'
  23     yield WaitDuration(0.2)
  24     print 'hi'
  25     yield WaitDuration(0.2)
  26     print 'Now I stop talking and wait'
  27     yield WaitTask(world_tid)
  28     print 'World is dead now'
  29     yield WaitDuration(1)
  30     print 'I liked world, I\'m tired, I will die...'
  31     sched.kill_task(tick_tid)
  32 
  33 rospy.init_node('teer_multiple_tasks')
  34 sched = Scheduler()
  35 sched.new_task(hello())
  36 sched.run()

In this example, the task hello() creates two new tasks, tick() that prints a tick 10 times per second and world(), that prints, wait, prints, and quit. We see that beside using WaitDuration, it is possible to wait by creating a Rate object using the create_rate() method on the scheduler, and then doing a yield Sleep using this object.

We also see that a task can stop and wait for another task to finish, using yield WaitTask with the task identifier as parameter. In addition, a task can also force another task to finish, by killing it using the kill_task() method on the scheduler. It is possible to wait for multiple tasks to finish, as we will see in the next tutorial.

Wiki: executive_teer/Tutorials/Multiple Tasks (last edited 2012-02-24 14:55:37 by StephaneMagnenat)