## For instruction on writing tutorials
## http://www.ros.org/wiki/WritingTutorials
####################################
##FILL ME IN
####################################
## for a custom note with links:
## note =
## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links 
## note.0= 
## descriptive title for the tutorial
## title = Iterator container
## multi-line description to be displayed in search 
## description = This tutorial teaches you how to use the Iterator container.
## the next tutorial description (optional)
## next =
## links to next tutorial (optional)
## next.0.link=[[smach/Tutorials/Wrapping a SMACH Container With actionlib|Wrapping a SMACH container with actionlib]]
## next.1.link=
## what level user is this tutorial for 
## level= BeginnerCategory
## keywords =
####################################

<<IncludeCSTemplate(TutorialCSHeaderTemplate)>>

<<TableOfContents(4)>>

=== Overview ===
The iterator allows you to loop through a state or states until success conditions are met. This tutorial demonstrates how to use an iterator to sort a list of numbers into evens and odds. 

=== The Code ===
Below is the full state machine, create a file called `iterator_tutorial.py` and copy the following code:

<<GetTaggedCode(https://raw.githubusercontent.com/eacousineau/executive_smach_tutorials/hydro-devel/smach_tutorials/examples/iterator_tutorial.py,python,FULLTEXT,show_uri,no_tag_newlines,global_lines)>>

=== The Code Explained ===
Start by constructing the iterator, the constructor takes the following arguments:
{{{
__init__(self, outcomes, input_keys, output_keys, it=[], it_label='it_data', exhausted_outcome='exhausted')
}}}
In this example, the `outcomes` now include `preempted`, a default `outcome` of the iterator. The `it` argument is the list of objects that will be iterated over and the `it_label` is key that holds the current value of the of the item in the `it` list. The `exhausted` argument should be set to the preferred state machine outcome, in this example the iterator outcome is `succeeded` when the iterator is done looping through the `it` list.

<<GetTaggedCode(https://raw.githubusercontent.com/eacousineau/executive_smach_tutorials/hydro-devel/smach_tutorials/examples/iterator_tutorial.py,python,ITERATOR,no_tag_newlines,global_lines)>>

Now add a container and create the states for sorting the list into even and odd. 
<<GetTaggedCode(https://raw.githubusercontent.com/eacousineau/executive_smach_tutorials/hydro-devel/smach_tutorials/examples/iterator_tutorial.py,python,CONTAINER,no_tag_newlines,global_lines)>>

Add the container to the iterator:

<<GetTaggedCode(https://raw.githubusercontent.com/eacousineau/executive_smach_tutorials/hydro-devel/smach_tutorials/examples/iterator_tutorial.py,python,ADDCONTAINER,no_tag_newlines,global_lines)>>

Finish by adding the iterator to the top level state machine:

<<GetTaggedCode(https://raw.githubusercontent.com/eacousineau/executive_smach_tutorials/hydro-devel/smach_tutorials/examples/iterator_tutorial.py,python,ADDITERATOR,no_tag_newlines,global_lines)>>

=== Running the Code ===
Make sure that a `roscore` is running:
{{{
$ roscore 
}}}
Run the `smach_viewer` so you can see the results:
{{{
$ rosrun smach_viewer smach_viewer.py
}}}
Now run the state machine:
{{{
$ sudo chmod a+x iterator_tutorial.py
$ python ./iterator_tutorial.py
}}}

{{attachment:smach_tutorial.png}}

## AUTOGENERATED DO NOT DELETE 
## TutorialCategory
## FILL IN THE STACK TUTORIAL CATEGORY HERE
## SMACHContainerCategory