Py Trees

Background

Introduction

Note

Behaviour trees are a decision making engine often used in the gaming industry.

Others include hierarchical finite state machines, task networks, and scripting engines, all of which have various pros and cons. Behaviour trees sit somewhere in the middle of these allowing you a good blend of purposeful planning towards goals with enough reactivity to shift in the presence of important events. They are also wonderfully simple to compose.

There’s much information already covering behaviour trees. Rather than regurgitating it here, dig through some of these first. A good starter is AI GameDev - Behaviour Trees (free signup and login) which puts behaviour trees in context alongside other techniques. A simpler read is Patrick Goebel’s Behaviour Trees For Robotics. Other readings are listed at the bottom of this page.

Some standout features of behaviour trees that makes them very attractive:

  • Ticking - the ability to tick allows for work between executions without multi-threading
  • Priority Handling - switching mechansims that allow higher priority interruptions is very natural
  • Simplicity - very few core components, making it easy for designers to work with it
  • Dynamic - change the graph on the fly, between ticks or from parent behaviours themselves

Motivation

The driving use case for this package was to implement a higher level decision making layer in robotics, i.e. scenarios with some overlap into the control layer. Behaviour trees turned out to be a much more apt fit to handle the many concurrent processes in a robot after attempts with finite state machines became entangled in wiring complexity as the problem grew in scope.

Note

There are very few open behaviour tree implementations.

Most of these have either not progressed significantly (e.g. Owyl), or are accessible only in some niche, e.g. Behaviour Designer, which is a frontend to the trees in the unity framework. Does this mean people do not use them? It is more probable that most behaviour tree implementations happen within the closed doors of gaming/robot companies.

Youtube - Second Generation of Behaviour Trees is an enlightening video about behaviour trees and the developments of the last ten years from an industry expert. It also walks you through a simple c++ implementation. His advice? If you can’t find one that fits, roll your own. It is relatively simple and this way you can flexibly cater for your own needs.

Design

The requirements for the previously discussed robotics use case match that of the more general:

Note

Rapid development of medium scale decision engines that don’t need to be real time reactive.

Developers should expect to be able to get up to speed and write their own trees with enough power and flexibility to adapt the library to their needs. Robotics is a good fit. The decision making layer typically does not grow too large (~ hundreds of behaviours) and does not need to handle the reactive decision making that is usually directly incorporated into the controller subsystems. On the other hand, it is not scoped to enable an NPC gaming engine with hundreds of characters and thousands of behaviours for each character.

This implementation uses all the whizbang tricks (generators, decorators) that python has to offer. Some design constraints that have been assumed to enable a practical, easy to use framework:

  • No interaction or sharing of data between tree instances
  • No parallelisation of tree execution
  • Only one behaviour initialising or executing at a time

Hint

A c++ version is feasible and may come forth if there’s a need..

Readings

Behaviours

A Behaviour is the smallest element in a behaviour tree, i.e. it is the leaf. Behaviours are usually representative of either a check (am I hungry?), or an action (buy some chocolate cookies).

Skeleton

Behaviours in py_trees are created by subclassing the Behaviour class. A skeleton example:

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
# doc/examples/skeleton_behaviour.py

import py_trees
import random


class Foo(py_trees.behaviour.Behaviour):
    def __init__(self, name):
        """
        Minimal one-time initialisation. A good rule of thumb is
        to only include the initialisation relevant for being able
        to insert this behaviour in a tree for offline rendering to
        dot graphs.

        Other one-time initialisation requirements should be met via
        the setup() method.
        """
        super(Foo, self).__init__(name)

    def setup(self):
        """
        When is this called?
          This function should be either manually called by your program
          to setup this behaviour alone, or more commonly, via
          :meth:`~py_trees.behaviour.Behaviour.setup_with_descendants`
          or :meth:`~py_trees.trees.BehaviourTree.setup`, both of which
          will iterate over this behaviour, it's children (it's children's
          children ...) calling :meth:`~py_trees.behaviour.Behaviour.setup`
          on each in turn.

          If you have vital initialisation necessary to the success
          execution of your behaviour, put a guard in your
          :meth:`~py_trees.behaviour.Behaviour.initialise` method
          to protect against entry without having been setup.

        What to do here?
          Delayed one-time initialisation that would otherwise interfere
          with offline rendering of this behaviour in a tree to dot graph
          or validation of the behaviour's configuration.

          Good examples include:

          - Hardware or driver initialisation
          - Middleware initialisation (e.g. ROS pubs/subs/services)
          - A parallel checking for a valid policy configuration after
            children have been added or removed
        """
        self.logger.debug("  %s [Foo::setup()]" % self.name)

    def initialise(self):
        """
        When is this called?
          The first time your behaviour is ticked and anytime the
          status is not RUNNING thereafter.

        What to do here?
          Any initialisation you need before putting your behaviour
          to work.
        """
        self.logger.debug("  %s [Foo::initialise()]" % self.name)

    def update(self):
        """
        When is this called?
          Every time your behaviour is ticked.

        What to do here?
          - Triggering, checking, monitoring. Anything...but do not block!
          - Set a feedback message
          - return a py_trees.common.Status.[RUNNING, SUCCESS, FAILURE]
        """
        self.logger.debug("  %s [Foo::update()]" % self.name)
        ready_to_make_a_decision = random.choice([True, False])
        decision = random.choice([True, False])
        if not ready_to_make_a_decision:
            return py_trees.common.Status.RUNNING
        elif decision:
            self.feedback_message = "We are not bar!"
            return py_trees.common.Status.SUCCESS
        else:
            self.feedback_message = "Uh oh"
            return py_trees.common.Status.FAILURE

    def terminate(self, new_status):
        """
        When is this called?
           Whenever your behaviour switches to a non-running state.
            - SUCCESS || FAILURE : your behaviour's work cycle has finished
            - INVALID : a higher priority branch has interrupted, or shutting down
        """
        self.logger.debug("  %s [Foo::terminate().terminate()][%s->%s]" % (self.name, self.status, new_status))

Lifecycle

Getting a feel for how this works in action can be seen by running the py-trees-demo-behaviour-lifecycle program (click the link for more detail and access to the sources):

_images/lifecycle.gif

Important points to focus on:

  • The initialise() method kicks in only when the behaviour is not already running
  • The parent tick() method is responsible for determining when to call initialise(), stop() and terminate() methods.
  • The parent tick() method always calls update()
  • The update() method is responsible for deciding the behaviour Status.

Initialisation

With no less than three methods used for initialisation, it can be difficult to identify where your initialisation code needs to lurk.

Note

__init__ should instantiate the behaviour sufficiently for offline dot graph generation

Later we’ll see how we can render trees of behaviours in dot graphs. For now, it is sufficient to understand that you need to keep this minimal enough so that you can generate dot graphs for your trees from something like a CI server (e.g. Jenkins). This is a very useful thing to be able to do.

  • No hardware connections that may not be there, e.g. usb lidars
  • No middleware connections to other software that may not be there, e.g. ROS pubs/subs/services
  • No need to fire up other needlessly heavy resources, e.g. heavy threads in the background

Note

setup handles all other one-time initialisations of resources that are required for execution

Essentially, all the things that the constructor doesn’t handle - hardware connections, middleware and other heavy resources.

Note

initialise configures and resets the behaviour ready for (repeated) execution

Initialisation here is about getting things ready for immediate execution of a task. Some examples:

  • Initialising/resetting/clearing variables
  • Starting timers
  • Just-in-time discovery and establishment of middleware connections
  • Sending a goal to start a controller running elsewhere on the system

Status

The most important part of a behaviour is the determination of the behaviour’s status in the update() method. The status gets used to affect which direction of travel is subsequently pursued through the remainder of a behaviour tree. We haven’t gotten to trees yet, but it is this which drives the decision making in a behaviour tree.

class py_trees.common.Status[source]

An enumerator representing the status of a behaviour

FAILURE = 'FAILURE'

Behaviour check has failed, or execution of its action finished with a failed result.

INVALID = 'INVALID'

Behaviour is uninitialised and inactive, i.e. this is the status before first entry, and after a higher priority switch has occurred.

RUNNING = 'RUNNING'

Behaviour is in the middle of executing some action, result still pending.

SUCCESS = 'SUCCESS'

Behaviour check has passed, or execution of its action has finished with a successful result.

The update() method must return one of RUNNING. SUCCESS or FAILURE. A status of INVALID is the initial default and ordinarily automatically set by other mechansims (e.g. when a higher priority behaviour cancels the currently selected one).

Feedback Message

1
2
3
4
        """
        Reset a counter variable.
        """
        self.logger.debug("%s.initialise()" % (self.__class__.__name__))

A behaviour has a naturally built in feedback message that can be cleared in the initialise() or terminate() methods and updated in the update() method.

Tip

Alter a feedback message when significant events occur.

The feedback message is designed to assist in notifying humans when a significant event happens or for deciding when to log the state of a tree. If you notify or log every tick, then you end up with a lot of noise sorting through an abundance of data in which nothing much is happening to find the one point where something significant occurred that led to surprising or catastrophic behaviour.

Setting the feedback message is usually important when something significant happens in the RUNNING state or to provide information associated with the result (e.g. failure reason).

Example - a behaviour responsible for planning motions of a character is in the RUNNING state for a long period of time. Avoid updating it with a feedback message at every tick with updated plan details. Instead, update the message whenever a significant change occurs - e.g. when the previous plan is re-planned or pre-empted.

Loggers

These are used throughout the demo programs. They are not intended to be for anything heavier than debugging simple examples. This kind of logging tends to get rather heavy and requires a lot of filtering to find the points of change that you are interested in (see comments about the feedback messages above).

Complex Example

The py-trees-demo-action-behaviour program demonstrates a more complicated behaviour that illustrates a few concepts discussed above, but not present in the very simple lifecycle Counter behaviour.

  • Mocks an external process and connects to it in the setup method
  • Kickstarts new goals with the external process in the initialise method
  • Monitors the ongoing goal status in the update method
  • Determines RUNNING/SUCCESS pending feedback from the external process

Note

A behaviour’s update() method never blocks, at most it just monitors the progress and holds up any decision making required by a tree that is ticking the behaviour by setting it’s status to RUNNING. At the risk of being confusing, this is what is generally referred to as a blocking behaviour.

_images/action.gif

Composites

Composites are the factories and decision makers of a behaviour tree. They are responsible for shaping the branches.

digraph selector {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Sequence [fontcolor=black, shape=box, fontsize=11, style=filled, fillcolor=orange];
Selector [fontcolor=black, shape=octagon, fontsize=11, style=filled, fillcolor=cyan];
Chooser [fontcolor=black, shape=doubleoctagon, fontsize=11, style=filled, fillcolor=cyan];
Parallel [fontcolor=black, shape=parallelogram, fontsize=11, style=filled, fillcolor=gold];
}

Tip

You should never need to subclass or create new composites.

Most patterns can be achieved with a combination of the above. Adding to this set exponentially increases the complexity and subsequently making it more difficult to design, introspect, visualise and debug the trees. Always try to find the combination you need to achieve your result before contemplating adding to this set. Actually, scratch that…just don’t contemplate it!

Composite behaviours typically manage children and apply some logic to the way they execute and return a result, but generally don’t do anything themselves. Perform the checks or actions you need to do in the non-composite behaviours.

  • Sequence: execute children sequentially
  • Selector: select a path through the tree, interruptible by higher priorities
  • Chooser: like a selector, but commits to a path once started until it finishes
  • Parallel: manage children concurrently

The subsections below introduce each composite briefly. For a full listing of each composite’s methods, visit the py_trees.composites module api documentation.

Tip

First time through, make sure to follow the link through to relevant demo programs.

Sequence

class py_trees.composites.Sequence(name='Sequence', children=None)[source]

Sequences are the factory lines of Behaviour Trees

digraph sequence {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Sequence [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
Guard [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Guard;
"Action 1" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 1";
"Action 2" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 2";
"Action 3" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 3";
}

A sequence will progressively tick over each of its children so long as each child returns SUCCESS. If any child returns FAILURE or RUNNING the sequence will halt and the parent will adopt the result of this child. If it reaches the last child, it returns with that result regardless.

Note

The sequence halts once it sees a child is RUNNING and then returns the result. It does not get stuck in the running behaviour.

See also

The py-trees-demo-sequence program demos a simple sequence in action.

Parameters:
  • name (str) – the composite behaviour name
  • children ([Behaviour]) – list of children to add

Selector

class py_trees.composites.Selector(name='Selector', children=None)[source]

Selectors are the Decision Makers

digraph selector {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Selector [fontcolor=black, shape=octagon, fontsize=11, style=filled, fillcolor=cyan];
"High Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Selector -> "High Priority";
"Med Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Selector -> "Med Priority";
"Low Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Selector -> "Low Priority";
}

A selector executes each of its child behaviours in turn until one of them succeeds (at which point it itself returns RUNNING or SUCCESS, or it runs out of children at which point it itself returns FAILURE. We usually refer to selecting children as a means of choosing between priorities. Each child and its subtree represent a decreasingly lower priority path.

Note

Switching from a low -> high priority branch causes a stop(INVALID) signal to be sent to the previously executing low priority branch. This signal will percolate down that child’s own subtree. Behaviours should make sure that they catch this and destruct appropriately.

Make sure you do your appropriate cleanup in the terminate() methods! e.g. cancelling a running goal, or restoring a context.

See also

The py-trees-demo-selector program demos higher priority switching under a selector.

Parameters:
  • name (str) – the composite behaviour name
  • children ([Behaviour]) – list of children to add

Chooser

class py_trees.composites.Chooser(name='Chooser', children=None)[source]

Choosers are Selectors with Commitment

digraph chooser {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Chooser [fontcolor=black, shape=doubleoctagon, fontsize=11, style=filled, fillcolor=cyan];
"High Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Chooser -> "High Priority";
"Med Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Chooser -> "Med Priority";
"Low Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Chooser -> "Low Priority";
}

A variant of the selector class. Once a child is selected, it cannot be interrupted by higher priority siblings. As soon as the chosen child itself has finished it frees the chooser for an alternative selection. i.e. priorities only come into effect if the chooser wasn’t running in the previous tick.

Note

This is the only composite in py_trees that is not a core composite in most behaviour tree implementations. Nonetheless, this is useful in fields like robotics, where you have to ensure that your manipulator doesn’t drop it’s payload mid-motion as soon as a higher interrupt arrives. Use this composite sparingly and only if you can’t find another way to easily create an elegant tree composition for your task.

Parameters:
  • name (str) – the composite behaviour name
  • children ([Behaviour]) – list of children to add

Parallel

class py_trees.composites.Parallel(name: str = <Name.AUTO_GENERATED: 'AUTO_GENERATED'>, policy: py_trees.common.ParallelPolicy.Base = <py_trees.common.ParallelPolicy.SuccessOnAll object>, children: List[py_trees.behaviour.Behaviour] = None)[source]

Parallels enable a kind of concurrency

digraph pastafarianism {
graph [fontname="times-roman", splines=curved];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Parallel [fillcolor=gold, fontcolor=black, fontsize=9, label="Parallel\n--SuccessOnSelected(⚡,[B1,B2])--", shape=parallelogram, style=filled];
B1 [fillcolor=gray, fontcolor=black, fontsize=9, label=B1, shape=ellipse, style=filled];
Parallel -> B1;
B2 [fillcolor=gray, fontcolor=black, fontsize=9, label=B2, shape=ellipse, style=filled];
Parallel -> B2;
B3 [fillcolor=gray, fontcolor=black, fontsize=9, label=B3, shape=ellipse, style=filled];
Parallel -> B3;
}

Ticks every child every time the parallel is run (a poor man’s form of parallelism).

Parallels with policy SuccessOnSelected will validate themselves just-in-time in the setup() and tick() methods to check if the policy’s selected set of children is a subset of the children of this parallel. Doing this just-in-time is due to the fact that the parallel’s children may change after construction and even dynamically between ticks.

Decorators

Decorators are behaviours that manage a single child and provide common modifications to their underlying child behaviour (e.g. inverting the result). That is, they provide a means for behaviours to wear different ‘hats’ and this combinatorially expands the capabilities of your behaviour library.

_images/many-hats.png

An example:

digraph life {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Life [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
Inverter [fillcolor=ghostwhite, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Life -> Inverter;
"Busy?" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Inverter -> "Busy?";
Timeout [fillcolor=ghostwhite, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Life -> Timeout;
"Have a Beer!" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Timeout -> "Have a Beer!";
}
 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
#!/usr/bin/env python

import py_trees.decorators
import py_trees.display

if __name__ == '__main__':

    root = py_trees.composites.Sequence(name="Life")
    timeout = py_trees.decorators.Timeout(
        name="Timeout",
        child=py_trees.behaviours.Success(name="Have a Beer!")
    )
    failure_is_success = py_trees.decorators.Inverter(
        name="Inverter",
        child=py_trees.behaviours.Success(name="Busy?")
        )
    root.add_children([failure_is_success, timeout])
    py_trees.display.render_dot_tree(root)

Decorators (Hats)

Decorators with very specific functionality:

And the X is Y family:

Decorators for Blocking Behaviours

It is worth making a note of the effect of decorators on behaviours that return RUNNING for some time before finally returning SUCCESS or FAILURE (blocking behaviours) since the results are often at first, surprising.

A decorator, such as py_trees.decorators.RunningIsSuccess() on a blocking behaviour will immediately terminate the underlying child and re-intialise on it’s next tick. This is necessary to ensure the underlying child isn’t left in a dangling state (i.e. RUNNING), but is often not what is being sought.

The typical use case being attempted is to convert the blocking behaviour into a non-blocking behaviour. If the underlying child has no state being modified in either the initialise() or terminate() methods (e.g. machinery is entirely launched at init or setup time), then conversion to a non-blocking representative of the original succeeds. Otherwise, another approach is needed. Usually this entails writing a non-blocking counterpart, or combination of behaviours to affect the non-blocking characteristics.

Blackboards

Blackboards are not a necessary component, but are a fairly standard feature in most behaviour tree implementations. See, for example, the design notes for blackboards in Unreal Engine.

_images/blackboard.jpg

Implementations however, tend to vary quite a bit depending on the needs of the framework using them. Some of the usual considerations include scope and sharing of blackboards across multiple tree instances.

For this package, we’ve decided to keep blackboards extremely simple to fit with the same ‘rapid development for small scale systems’ principles that this library is designed for.

  • No sharing between tree instances
  • No locking for reading/writing
  • Global scope, i.e. any behaviour can access any variable
  • No external communications (e.g. to a database)
class py_trees.blackboard.Blackboard[source]

Borg style key-value store for sharing amongst behaviours.

Examples

You can instantiate the blackboard from anywhere in your program. Even disconnected calls will get access to the same data store. For example:

def check_foo():
    blackboard = Blackboard()
    assert(blackboard.foo, "bar")

if __name__ == '__main__':
    blackboard = Blackboard()
    blackboard.foo = "bar"
    check_foo()

If the key value you are interested in is only known at runtime, then you can set/get from the blackboard without the convenient variable style access:

blackboard = Blackboard()
result = blackboard.set("foo", "bar")
foo = blackboard.get("foo")

The blackboard can also be converted and printed (with highlighting) as a string. This is useful for logging and debugging.

print(Blackboard())

Warning

Be careful of key collisions. This implementation leaves this management up to the user.

See also

The py-trees-demo-blackboard program demos use of the blackboard along with a couple of the blackboard behaviours.

Idioms

A library of subtree creators that build complex patterns of behaviours representing common behaviour tree idioms.

Common decision making patterns can often be realised using a specific combination of fundamental behaviours and the blackboard. Even if this somewhat verbosely populates the tree, this is preferable to creating new composites types or overriding existing composites since this will increase tree logic complexity and/or bury details under the hood (both of which add an exponential cost to introspection/visualisation).

In this package these patterns will be referred to as PyTree Idioms and in this module you will find convenience functions that assist in creating them.

The subsections below introduce each composite briefly. For a full listing of each composite’s methods, visit the py_trees.idioms module api documentation.

Tip

First time through, make sure to follow the link through to relevant demo programs.

Oneshot

idioms.oneshot(variable_name='oneshot', behaviour=<py_trees.meta.Dummy object>, policy=<OneShotPolicy.ON_SUCCESSFUL_COMPLETION: [<Status.SUCCESS: 'SUCCESS'>]>)

Ensure that a particular pattern is executed through to completion just once. Thereafter it will just rebound with success.

digraph oneshot {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
OneShot [fillcolor=cyan, fontcolor=black, fontsize=11, shape=octagon, style=filled];
"Oneshot w/ Guard" [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
OneShot -> "Oneshot w/ Guard";
"Not Completed?" [fillcolor=ghostwhite, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Oneshot w/ Guard" -> "Not Completed?";
"Completed?" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Not Completed?" -> "Completed?";
Sequence [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
"Oneshot w/ Guard" -> Sequence;
Guard [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Guard;
"Action 1" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 1";
"Action 2" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 2";
"Action 3" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 3";
"Mark Done\n[SUCCESS]" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Mark Done\n[SUCCESS]";
"Oneshot Result" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
OneShot -> "Oneshot Result";
}

Note

Completion on FAILURE or on SUCCESS only (permits retries if it fails) is determined by the policy.

Parameters:
  • name (str) – the name to use for the oneshot root (selector)
  • variable_name (str) – name for the flag used on the blackboard (ensure it is unique)
  • behaviour (Behaviour) – single behaviour or composited subtree to oneshot
  • policy (OneShotPolicy) – policy determining when the oneshot should activate
Returns:

the root of the oneshot subtree

Return type:

Behaviour

Pickup Where You left Off

idioms.pick_up_where_you_left_off(tasks=[<py_trees.meta.Dummy object>, <py_trees.meta.Dummy object>])

Rudely interrupted while enjoying a sandwich, a caveman (just because they wore loincloths does not mean they were not civilised), picks up his club and fends off the sabre-tooth tiger invading his sanctum as if he were swatting away a gnat. Task accomplished, he returns to the joys of munching through the layers of his sandwich.

digraph pick_up_where_you_left_off {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
"Pick Up Where You Left Off" [shape=octagon, style=filled, fillcolor=cyan, fontsize=11, fontcolor=black];
"High Priority" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Pick Up Where You Left Off" -> "High Priority";
Tasks [shape=box, style=filled, fillcolor=orange, fontsize=11, fontcolor=black];
"Pick Up Where You Left Off" -> Tasks;
"Do or Don't" [shape=octagon, style=filled, fillcolor=cyan, fontsize=11, fontcolor=black];
Tasks -> "Do or Don't";
"Done?" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Do or Don't" -> "Done?";
Worker [shape=box, style=filled, fillcolor=orange, fontsize=11, fontcolor=black];
"Do or Don't" -> Worker;
"Task 1" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Worker -> "Task 1";
"Mark\ntask_1_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Worker -> "Mark\ntask_1_done";
"Do or Don't*" [shape=octagon, style=filled, fillcolor=cyan, fontsize=11, fontcolor=black];
Tasks -> "Do or Don't*";
"Done?*" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Do or Don't*" -> "Done?*";
"Worker*" [shape=box, style=filled, fillcolor=orange, fontsize=11, fontcolor=black];
"Do or Don't*" -> "Worker*";
"Task 2" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Worker*" -> "Task 2";
"Mark\ntask_2_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Worker*" -> "Mark\ntask_2_done";
"Clear\ntask_1_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Tasks -> "Clear\ntask_1_done";
"Clear\ntask_2_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Tasks -> "Clear\ntask_2_done";
}

Note

There are alternative ways to accomplish this idiom with their pros and cons.

a) The tasks in the sequence could be replaced by a factory behaviour that dynamically checks the state of play and spins up the tasks required each time the task sequence is first entered and invalidates/deletes them when it is either finished or invalidated. That has the advantage of not requiring much of the blackboard machinery here, but disadvantage in not making visible the task sequence itself at all times (i.e. burying details under the hood).

b) A new composite which retains the index between initialisations can also achieve the same pattern with fewer blackboard shenanigans, but suffers from an increased logical complexity cost for your trees (each new composite increases decision making complexity (O(n!)).

Parameters:
  • name (str) – the name to use for the task sequence behaviour
  • tasks ([Behaviour) – lists of tasks to be sequentially performed
Returns:

root of the generated subtree

Return type:

Behaviour

Trees

The Behaviour Tree

class py_trees.trees.BehaviourTree(root: py_trees.behaviour.Behaviour)[source]

Grow, water, prune your behaviour tree with this, the default reference implementation. It features a few enhancements to provide richer logging, introspection and dynamic management of the tree itself:

  • Pre and post tick handlers to execute code automatically before and after a tick
  • Visitor access to the parts of the tree that were traversed in a tick
  • Subtree pruning and insertion operations
  • Continuous tick-tock support

See also

The py-trees-demo-tree-stewardship program demonstrates the above features.

Parameters:

root (Behaviour) – root node of the tree

Variables:
  • count (int) – number of times the tree has been ticked.
  • root (Behaviour) – root node of the tree
  • visitors ([visitors]) – entities that visit traversed parts of the tree when it ticks
  • pre_tick_handlers ([func]) – functions that run before the entire tree is ticked
  • post_tick_handlers ([func]) – functions that run after the entire tree is ticked
Raises:

TypeError – if root variable is not an instance of Behaviour

Skeleton

The most basic feature of the behaviour tree is it’s automatic tick-tock. You can tick_tock() for a specific number of iterations, or indefinitely and use the interrupt() method to stop it.

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
#!/usr/bin/env python

import py_trees

if __name__ == '__main__':

    root = py_trees.composites.Selector("Selector")
    high = py_trees.behaviours.Success(name="High Priority")
    med = py_trees.behaviours.Success(name="Med Priority")
    low = py_trees.behaviours.Success(name="Low Priority")
    root.add_children([high, med, low])

    behaviour_tree = py_trees.trees.BehaviourTree(root)
    behaviour_tree.setup(timeout=15)
    try:
        behaviour_tree.tick_tock(
            sleep_ms=500,
            number_of_iterations=py_trees.trees.CONTINUOUS_TICK_TOCK,
            pre_tick_handler=None,
            post_tick_handler=None
        )
    except KeyboardInterrupt:
        behaviour_tree.interrupt()

or create your own loop and tick at your own leisure with the tick() method.

Pre/Post Tick Handlers

Pre and post tick handlers can be used to perform some activity on or with the tree immediately before and after ticking. This is mostly useful with the continuous tick_tock() mechanism.

This is useful for a variety of purposes:

  • logging
  • doing introspection on the tree to make reports
  • extracting data from the blackboard
  • triggering on external conditions to modify the tree (e.g. new plan arrived)

This can be done of course, without locking since the tree won’t be ticking while these handlers run. This does however, mean that your handlers should be light. They will be consuming time outside the regular tick period.

The py-trees-demo-tree-stewardship program demonstrates a very simple pre-tick handler that just prints a line to stdout notifying the user of the current run. The relevant code:

pre-tick-handler-function
 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11


def pre_tick_handler(behaviour_tree):
    """
    This prints a banner and will run immediately before every tick of the tree.

    Args:
        behaviour_tree (:class:`~py_trees.trees.BehaviourTree`): the tree custodian

    """
    print("\n--------- Run %s ---------\n" % behaviour_tree.count)
pre-tick-handler-adding
1
2
    print(description(tree))

Visitors

Visitors are entities that can be passed to a tree implementation (e.g. BehaviourTree) and used to either visit each and every behaviour in the tree, or visit behaviours as the tree is traversed in an executing tick. At each behaviour, the visitor runs its own method on the behaviour to do as it wishes - logging, introspecting, etc.

Warning

Visitors should not modify the behaviours they visit.

The py-trees-demo-tree-stewardship program demonstrates the two reference visitor implementations:

Adding visitors to a tree:

behaviour_tree = py_trees.trees.BehaviourTree(root)
behaviour_tree.visitors.append(py_trees.visitors.DebugVisitor())
snapshot_visitor = py_trees.visitors.SnapshotVisitor()
behaviour_tree.visitors.append(snapshot_visitor)

These visitors are automatically run inside the tree’s tick method. The former immediately logs to screen, the latter collects information which is then used to display an ascii tree:

behaviour_tree.tick()
ascii_tree = py_trees.display.ascii_tree(
    behaviour_tree.root,
    snapshot_information=snapshot_visitor)
)
print(ascii_tree)

Visualisation

Behaviour trees are significantly easier to design, monitor and debug with visualisations. Py Trees does provide minimal assistance to render trees to various simple output formats. Currently this includes dot graphs, strings or stdout.

Warning

There is both disrespect for ascii and lack of recognition for unicode in this file as the intention to make ascii art a first class citizen in py_trees became tainted by the desire to make use of the very fine looking unicode symbols underneath. If such behaviour offends, please wear your peril-sensitive sunglasses when parsing or using this module.

Ascii Trees

You can get an ascii art representation of the tree on stdout with ascii_tree():

py_trees.display.ascii_tree(root, show_status=False, visited={}, previously_visited={}, indent=0)[source]

Graffiti your console with with ascii trees.

Parameters:
  • root (Behaviour) – the root of the tree, or subtree you want to show
  • indent (int) – the number of characters to indent the tree
  • show_status (bool) – always show status and feedback message (i.e. for every element, not just those visited)
  • visited (dict) – dictionary of (uuid.UUID) and status (Status) pairs for behaviours visited on the current tick
  • previously_visited (dict) – dictionary of behaviour id/status pairs from the previous tree tick
Returns:

an ascii tree (i.e. in string form)

Return type:

str

Examples

Use the SnapshotVisitor and BehaviourTree to generate snapshot information at each tick and feed that to a post tick handler that will print the traversed ascii tree complete with status and feedback messages.

_images/ascii_tree.png
def post_tick_handler(snapshot_visitor, behaviour_tree):
    print(
        py_trees.display.ascii_tree(
            behaviour_tree.root,
            visited=snapshot_visitor.visited,
            previously_visited=snapshot_visitor.visited
        )
    )

root = py_trees.composites.Sequence("Sequence")
for action in ["Action 1", "Action 2", "Action 3"]:
    b = py_trees.behaviours.Count(
            name=action,
            fail_until=0,
            running_until=1,
            success_until=10)
    root.add_child(b)
behaviour_tree = py_trees.trees.BehaviourTree(root)
snapshot_visitor = py_trees.visitors.SnapshotVisitor()
behaviour_tree.add_post_tick_handler(
    functools.partial(post_tick_handler,
                      snapshot_visitor))
behaviour_tree.visitors.append(snapshot_visitor)

Ascii Trees (Runtime)

When a tree is ticking, it is important to be able to catch the status and feedback message from each behaviour that has been traversed. You can do this by using the SnapshotVisitor in conjunction with the ascii_tree() function:

py_trees.display.ascii_tree(root, show_status=False, visited={}, previously_visited={}, indent=0)[source]

Graffiti your console with with ascii trees.

Parameters:
  • root (Behaviour) – the root of the tree, or subtree you want to show
  • indent (int) – the number of characters to indent the tree
  • show_status (bool) – always show status and feedback message (i.e. for every element, not just those visited)
  • visited (dict) – dictionary of (uuid.UUID) and status (Status) pairs for behaviours visited on the current tick
  • previously_visited (dict) – dictionary of behaviour id/status pairs from the previous tree tick
Returns:

an ascii tree (i.e. in string form)

Return type:

str

Examples

Use the SnapshotVisitor and BehaviourTree to generate snapshot information at each tick and feed that to a post tick handler that will print the traversed ascii tree complete with status and feedback messages.

_images/ascii_tree.png
def post_tick_handler(snapshot_visitor, behaviour_tree):
    print(
        py_trees.display.ascii_tree(
            behaviour_tree.root,
            visited=snapshot_visitor.visited,
            previously_visited=snapshot_visitor.visited
        )
    )

root = py_trees.composites.Sequence("Sequence")
for action in ["Action 1", "Action 2", "Action 3"]:
    b = py_trees.behaviours.Count(
            name=action,
            fail_until=0,
            running_until=1,
            success_until=10)
    root.add_child(b)
behaviour_tree = py_trees.trees.BehaviourTree(root)
snapshot_visitor = py_trees.visitors.SnapshotVisitor()
behaviour_tree.add_post_tick_handler(
    functools.partial(post_tick_handler,
                      snapshot_visitor))
behaviour_tree.visitors.append(snapshot_visitor)

Render to File (Dot/SVG/PNG)

API

You can render trees into dot/png/svg files simply by calling the render_dot_tree() function.

Should you wish to capture the dot graph result directly (as a dot graph object), use the generate_pydot_graph() method.

Command Line Utility

You can also render any exposed method in your python packages that creates a tree and returns the root of the tree from the command line using the py-trees-render program.

Blackboxes and Visibility Levels

There is also an experimental feature that allows you to flag behaviours as blackboxes with multiple levels of granularity. This is purely for the purposes of showing different levels of detail in rendered dot graphs. A fullly rendered dot graph with hundreds of behaviours is not of much use when wanting to visualise the big picture.

The py-trees-demo-dot-graphs program serves as a self-contained example of this feature.

Surviving the Crazy Hospital

Your behaviour trees are misbehaving or your subtree designs seem overly obtuse? This page can help you stay focused on what is important…staying out of the padded room.

_images/crazy_hospital.jpg

Note

Many of these guidelines we’ve evolved from trial and error and are almost entirely driven by a need to avoid a burgeoning complexity (aka flying spaghetti monster). Feel free to experiment and provide us with your insights here as well!

Behaviours

  • Keep the constructor minimal so you can instantiate the behaviour for offline rendering
  • Put hardware or other runtime specific initialisation in setup()
  • Update feedback_message for significant events only so you don’t end up with too much noise
  • The update() method must be light and non-blocking so a tree can keep ticking over
  • Keep the scope of a single behaviour tight and focused, deploy larger concepts as subtrees

Composites

  • Avoid creating new composites, this increases the decision complexity by an order of magnitude
  • Don’t subclass merely to auto-populate it, build a create_<xyz>_subtree() library instead

Trees

  • Make sure your pre/post tick handlers and visitors are all very light.
  • A good tick-tock rate for higher level decision making is around 500ms.

Terminology

blocking
A behaviour is sometimes referred to as a ‘blocking’ behaviour. Technically, the execution of a behaviour should be non-blocking (i.e. the tick part), however when it’s progress from ‘RUNNING’ to ‘FAILURE/SUCCESS’ takes more than one tick, we say that the behaviour itself is blocking. In short, blocking == RUNNING.
fsm
flying spaghetti monster

Whilst a serious religous entity in his own right (see pastafarianism), it’s also very easy to imagine your code become a spiritual flying spaghetti monster if left unchecked:

  _  _(o)_(o)_  _
._\`:_ F S M _:' \_,
    / (`---'\ `-.
 ,-`  _)    (_,
tick
ticks
ticking

A key feature of behaviours and their trees is in the way they tick. A tick is merely an execution slice, similar to calling a function once, or executing a loop in a control program once.

When a behaviour ticks, it is executing a small, non-blocking chunk of code that checks a variable or triggers/monitors/returns the result of an external action.

When a behaviour tree ticks, it traverses the behaviours (starting at the root of the tree), ticking each behaviour, catching its result and then using that result to make decisions on the direction the tree traversal will take. This is the decision part of the tree. Once the traversal ends back at the root, the tick is over.

Once a tick is done..you can stop for breath! In this space you can pause to avoid eating the cpu, send some statistics out to a monitoring program, manipulate the underlying blackboard (data), … At no point does the traversal of the tree get mired in execution - it’s just in and out and then stop for a coffee. This is absolutely awesome - without this it would be a concurrent mess of locks and threads.

Always keep in mind that your behaviours’ executions must be light. There is no parallelising here and your tick time needs to remain small. The tree should be solely about decision making, not doing any actual blocking work. Any blocking work should be happening somewhere else with a behaviour simply in charge of starting/monitoring and catching the result of that work.

Add an image of a ticking tree here.

FAQ

Tip

For hints and guidelines, you might also like to browse Surviving the Crazy Hospital.

Will there be a c++ implementation?

Certainly feasible and if there’s a need. If such a things should come to pass though, the c++ implementation should compliment this one. That is, it should focus on decision making for systems with low latency and reactive requirements. It would use triggers to tick the tree instead of tick-tock and a few other tricks that have evolved in the gaming industry over the last few years. Having a c++ implementation for use in the control layer of a robotics system would be a driving use case.

Demos

py-trees-demo-action-behaviour

Demonstrates the characteristics of a typical ‘action’ behaviour.

  • Mocks an external process and connects to it in the setup() method
  • Kickstarts new goals with the external process in the initialise() method
  • Monitors the ongoing goal status in the update() method
  • Determines RUNNING/SUCCESS pending feedback from the external process

usage: py-trees-demo-action-behaviour [-h]
_images/action.gif
class py_trees.demos.action.Action(name='Action')[source]

Bases: py_trees.behaviour.Behaviour

Connects to a subprocess to initiate a goal, and monitors the progress of that goal at each tick until the goal is completed, at which time the behaviour itself returns with success or failure (depending on success or failure of the goal itself).

This is typical of a behaviour that is connected to an external process responsible for driving hardware, conducting a plan, or a long running processing pipeline (e.g. planning/vision).

Key point - this behaviour itself should not be doing any work!

__init__(name='Action')[source]

Default construction.

initialise()[source]

Reset a counter variable.

setup()[source]

No delayed initialisation required for this example.

terminate(new_status)[source]

Nothing to clean up in this example.

update()[source]

Increment the counter and decide upon a new status result for the behaviour.

py_trees.demos.action.main()[source]

Entry point for the demo script.

py_trees.demos.action.planning(pipe_connection)[source]

Emulates an external process which might accept long running planning jobs.

py_trees/demos/action.py
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
#!/usr/bin/env python
#
# License: BSD
#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE
#
##############################################################################
# Documentation
##############################################################################

"""
.. argparse::
   :module: py_trees.demos.action
   :func: command_line_argument_parser
   :prog: py-trees-demo-action-behaviour

.. image:: images/action.gif
"""

##############################################################################
# Imports
##############################################################################

import argparse
import atexit
import multiprocessing
import py_trees.common
import time

import py_trees.console as console

##############################################################################
# Classes
##############################################################################


def description():
    content = "Demonstrates the characteristics of a typical 'action' behaviour.\n"
    content += "\n"
    content += "* Mocks an external process and connects to it in the setup() method\n"
    content += "* Kickstarts new goals with the external process in the initialise() method\n"
    content += "* Monitors the ongoing goal status in the update() method\n"
    content += "* Determines RUNNING/SUCCESS pending feedback from the external process\n"

    if py_trees.console.has_colours:
        banner_line = console.green + "*" * 79 + "\n" + console.reset
        s = "\n"
        s += banner_line
        s += console.bold_white + "Action Behaviour".center(79) + "\n" + console.reset
        s += banner_line
        s += "\n"
        s += content
        s += "\n"
        s += banner_line
    else:
        s = content
    return s


def epilog():
    if py_trees.console.has_colours:
        return console.cyan + "And his noodly appendage reached forth to tickle the blessed...\n" + console.reset
    else:
        return None


def command_line_argument_parser():
    return argparse.ArgumentParser(description=description(),
                                   epilog=epilog(),
                                   formatter_class=argparse.RawDescriptionHelpFormatter,
                                   )


def planning(pipe_connection):
    """
    Emulates an external process which might accept long running planning jobs.
    """
    idle = True
    percentage_complete = 0
    try:
        while(True):
            if pipe_connection.poll():
                pipe_connection.recv()
                percentage_complete = 0
                idle = False
            if not idle:
                percentage_complete += 10
                pipe_connection.send([percentage_complete])
                if percentage_complete == 100:
                    idle = True
            time.sleep(0.5)
    except KeyboardInterrupt:
        pass


class Action(py_trees.behaviour.Behaviour):
    """
    Connects to a subprocess to initiate a goal, and monitors the progress
    of that goal at each tick until the goal is completed, at which time
    the behaviour itself returns with success or failure (depending on
    success or failure of the goal itself).

    This is typical of a behaviour that is connected to an external process
    responsible for driving hardware, conducting a plan, or a long running
    processing pipeline (e.g. planning/vision).

    Key point - this behaviour itself should not be doing any work!
    """
    def __init__(self, name="Action"):
        """
        Default construction.
        """
        super(Action, self).__init__(name)
        self.logger.debug("%s.__init__()" % (self.__class__.__name__))

    def setup(self):
        """
        No delayed initialisation required for this example.
        """
        self.logger.debug("%s.setup()->connections to an external process" % (self.__class__.__name__))
        self.parent_connection, self.child_connection = multiprocessing.Pipe()
        self.planning = multiprocessing.Process(target=planning, args=(self.child_connection,))
        atexit.register(self.planning.terminate)
        self.planning.start()

    def initialise(self):
        """
        Reset a counter variable.
        """
        self.logger.debug("%s.initialise()->sending new goal" % (self.__class__.__name__))
        self.parent_connection.send(['new goal'])
        self.percentage_completion = 0

    def update(self):
        """
        Increment the counter and decide upon a new status result for the behaviour.
        """
        new_status = py_trees.common.Status.RUNNING
        if self.parent_connection.poll():
            self.percentage_completion = self.parent_connection.recv().pop()
            if self.percentage_completion == 100:
                new_status = py_trees.common.Status.SUCCESS
        if new_status == py_trees.common.Status.SUCCESS:
            self.feedback_message = "Processing finished"
            self.logger.debug("%s.update()[%s->%s][%s]" % (self.__class__.__name__, self.status, new_status, self.feedback_message))
        else:
            self.feedback_message = "{0}%".format(self.percentage_completion)
            self.logger.debug("%s.update()[%s][%s]" % (self.__class__.__name__, self.status, self.feedback_message))
        return new_status

    def terminate(self, new_status):
        """
        Nothing to clean up in this example.
        """
        self.logger.debug("%s.terminate()[%s->%s]" % (self.__class__.__name__, self.status, new_status))


##############################################################################
# Main
##############################################################################

def main():
    """
    Entry point for the demo script.
    """
    command_line_argument_parser().parse_args()

    print(description())

    py_trees.logging.level = py_trees.logging.Level.DEBUG

    action = Action()
    action.setup()
    try:
        for unused_i in range(0, 12):
            action.tick_once()
            time.sleep(0.5)
        print("\n")
    except KeyboardInterrupt:
        pass

py-trees-demo-behaviour-lifecycle

Demonstrates a typical day in the life of a behaviour.

This behaviour will count from 1 to 3 and then reset and repeat. As it does so, it logs and displays the methods as they are called - construction, setup, initialisation, ticking and termination.

usage: py-trees-demo-behaviour-lifecycle [-h]
_images/lifecycle.gif
class py_trees.demos.lifecycle.Counter(name='Counter')[source]

Bases: py_trees.behaviour.Behaviour

Simple counting behaviour that facilitates the demonstration of a behaviour in the demo behaviours lifecycle program.

  • Increments a counter from zero at each tick
  • Finishes with success if the counter reaches three
  • Resets the counter in the initialise() method.
__init__(name='Counter')[source]

Default construction.

initialise()[source]

Reset a counter variable.

setup()[source]

No delayed initialisation required for this example.

terminate(new_status)[source]

Nothing to clean up in this example.

update()[source]

Increment the counter and decide upon a new status result for the behaviour.

py_trees.demos.lifecycle.main()[source]

Entry point for the demo script.

py_trees/demos/lifecycle.py
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
#!/usr/bin/env python
#
# License: BSD
#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE
#
##############################################################################
# Documentation
##############################################################################

"""
.. argparse::
   :module: py_trees.demos.lifecycle
   :func: command_line_argument_parser
   :prog: py-trees-demo-behaviour-lifecycle

.. image:: images/lifecycle.gif
"""

##############################################################################
# Imports
##############################################################################

import argparse
import py_trees
import time

import py_trees.console as console

##############################################################################
# Classes
##############################################################################


def description():
    content = "Demonstrates a typical day in the life of a behaviour.\n\n"
    content += "This behaviour will count from 1 to 3 and then reset and repeat. As it does\n"
    content += "so, it logs and displays the methods as they are called - construction, setup,\n"
    content += "initialisation, ticking and termination.\n"
    if py_trees.console.has_colours:
        banner_line = console.green + "*" * 79 + "\n" + console.reset
        s = "\n"
        s += banner_line
        s += console.bold_white + "Behaviour Lifecycle".center(79) + "\n" + console.reset
        s += banner_line
        s += "\n"
        s += content
        s += "\n"
        s += banner_line
    else:
        s = content
    return s


def epilog():
    if py_trees.console.has_colours:
        return console.cyan + "And his noodly appendage reached forth to tickle the blessed...\n" + console.reset
    else:
        return None


def command_line_argument_parser():
    return argparse.ArgumentParser(description=description(),
                                   epilog=epilog(),
                                   formatter_class=argparse.RawDescriptionHelpFormatter,
                                   )


class Counter(py_trees.behaviour.Behaviour):
    """
    Simple counting behaviour that facilitates the demonstration of a behaviour in
    the demo behaviours lifecycle program.

    * Increments a counter from zero at each tick
    * Finishes with success if the counter reaches three
    * Resets the counter in the initialise() method.
    """
    def __init__(self, name="Counter"):
        """
        Default construction.
        """
        super(Counter, self).__init__(name)
        self.logger.debug("%s.__init__()" % (self.__class__.__name__))

    def setup(self):
        """
        No delayed initialisation required for this example.
        """
        self.logger.debug("%s.setup()" % (self.__class__.__name__))

    def initialise(self):
        """
        Reset a counter variable.
        """
        self.logger.debug("%s.initialise()" % (self.__class__.__name__))
        self.counter = 0

    def update(self):
        """
        Increment the counter and decide upon a new status result for the behaviour.
        """
        self.counter += 1
        new_status = py_trees.common.Status.SUCCESS if self.counter == 3 else py_trees.common.Status.RUNNING
        if new_status == py_trees.common.Status.SUCCESS:
            self.feedback_message = "counting...{0} - phew, thats enough for today".format(self.counter)
        else:
            self.feedback_message = "still counting"
        self.logger.debug("%s.update()[%s->%s][%s]" % (self.__class__.__name__, self.status, new_status, self.feedback_message))
        return new_status

    def terminate(self, new_status):
        """
        Nothing to clean up in this example.
        """
        self.logger.debug("%s.terminate()[%s->%s]" % (self.__class__.__name__, self.status, new_status))


##############################################################################
# Main
##############################################################################

def main():
    """
    Entry point for the demo script.
    """
    command_line_argument_parser().parse_args()

    print(description())

    py_trees.logging.level = py_trees.logging.Level.DEBUG

    counter = Counter()
    counter.setup()
    try:
        for unused_i in range(0, 7):
            counter.tick_once()
            time.sleep(0.5)
        print("\n")
    except KeyboardInterrupt:
        print("")
        pass

py-trees-demo-blackboard

Demonstrates usage of the blackboard and related behaviours.

A sequence is populated with a default set blackboard variable behaviour, a custom write to blackboard behaviour that writes a more complicated structure, and finally a default check blackboard variable beheaviour that looks for the first variable.

usage: py-trees-demo-blackboard [-h] [-r]

Named Arguments

-r, --render

render dot tree to file

Default: False

digraph sequence {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Sequence [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
"Set Foo" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Set Foo";
Writer [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Writer;
"Check Foo" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Check Foo";
}
_images/blackboard.gif
class py_trees.demos.blackboard.BlackboardWriter(name='Writer')[source]

Bases: py_trees.behaviour.Behaviour

Custom writer that submits a more complicated variable to the blackboard.

__init__(name='Writer')[source]

Initialize self. See help(type(self)) for accurate signature.

update()[source]

Write a dictionary to the blackboard and return SUCCESS.

py_trees.demos.blackboard.main()[source]

Entry point for the demo script.

py_trees/demos/blackboard.py
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
#!/usr/bin/env python
#
# License: BSD
#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE
#
##############################################################################
# Documentation
##############################################################################

"""
.. argparse::
   :module: py_trees.demos.blackboard
   :func: command_line_argument_parser
   :prog: py-trees-demo-blackboard

.. graphviz:: dot/demo-blackboard.dot

.. image:: images/blackboard.gif
"""

##############################################################################
# Imports
##############################################################################

import argparse
import py_trees
import sys

import py_trees.console as console

##############################################################################
# Classes
##############################################################################


def description():
    content = "Demonstrates usage of the blackboard and related behaviours.\n"
    content += "\n"
    content += "A sequence is populated with a default set blackboard variable\n"
    content += "behaviour, a custom write to blackboard behaviour that writes\n"
    content += "a more complicated structure, and finally a default check\n"
    content += "blackboard variable beheaviour that looks for the first variable.\n"

    if py_trees.console.has_colours:
        banner_line = console.green + "*" * 79 + "\n" + console.reset
        s = "\n"
        s += banner_line
        s += console.bold_white + "Blackboard".center(79) + "\n" + console.reset
        s += banner_line
        s += "\n"
        s += content
        s += "\n"
        s += banner_line
    else:
        s = content
    return s


def epilog():
    if py_trees.console.has_colours:
        return console.cyan + "And his noodly appendage reached forth to tickle the blessed...\n" + console.reset
    else:
        return None


def command_line_argument_parser():
    parser = argparse.ArgumentParser(description=description(),
                                     epilog=epilog(),
                                     formatter_class=argparse.RawDescriptionHelpFormatter,
                                     )
    parser.add_argument('-r', '--render', action='store_true', help='render dot tree to file')
    return parser


class BlackboardWriter(py_trees.behaviour.Behaviour):
    """
    Custom writer that submits a more complicated variable to the blackboard.
    """
    def __init__(self, name="Writer"):
        super(BlackboardWriter, self).__init__(name)
        self.logger.debug("%s.__init__()" % (self.__class__.__name__))
        self.blackboard = py_trees.blackboard.Blackboard()

    def update(self):
        """
        Write a dictionary to the blackboard and return :data:`~py_trees.common.Status.SUCCESS`.
        """
        self.logger.debug("%s.update()" % (self.__class__.__name__))
        self.blackboard.spaghetti = {"type": "Gnocchi", "quantity": 2}
        return py_trees.common.Status.SUCCESS


def create_root():
    root = py_trees.composites.Sequence("Sequence")
    set_blackboard_variable = py_trees.blackboard.SetBlackboardVariable(name="Set Foo", variable_name="foo", variable_value="bar")
    write_blackboard_variable = BlackboardWriter(name="Writer")
    check_blackboard_variable = py_trees.blackboard.CheckBlackboardVariable(name="Check Foo", variable_name="foo", expected_value="bar")
    root.add_children([set_blackboard_variable, write_blackboard_variable, check_blackboard_variable])
    return root


##############################################################################
# Main
##############################################################################

def main():
    """
    Entry point for the demo script.
    """
    args = command_line_argument_parser().parse_args()
    print(description())
    py_trees.logging.level = py_trees.logging.Level.DEBUG

    root = create_root()

    ####################
    # Rendering
    ####################
    if args.render:
        py_trees.display.render_dot_tree(root)
        sys.exit()

    ####################
    # Execute
    ####################
    root.setup_with_descendants()
    print("\n--------- Tick 0 ---------\n")
    root.tick_once()
    print("\n")
    print(py_trees.display.ascii_tree(root, show_status=True))
    print("\n")
    print(py_trees.blackboard.Blackboard())

py-trees-demo-context-switching

Demonstrates context switching with parallels and sequences.

A context switching behaviour is run in parallel with a work sequence. Switching the context occurs in the initialise() and terminate() methods of the context switching behaviour. Note that whether the sequence results in failure or success, the context switch behaviour will always call the terminate() method to restore the context. It will also call terminate() to restore the context in the event of a higher priority parent cancelling this parallel subtree.

usage: py-trees-demo-context-switching [-h] [-r]

Named Arguments

-r, --render

render dot tree to file

Default: False

digraph parallel {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Parallel [fillcolor=gold, fontcolor=black, fontsize=11, shape=note, style=filled];
Context [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Parallel -> Context;
Sequence [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
Parallel -> Sequence;
"Action 1" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 1";
"Action 2" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 2";
}
_images/context_switching.gif
class py_trees.demos.context_switching.ContextSwitch(name='ContextSwitch')[source]

Bases: py_trees.behaviour.Behaviour

An example of a context switching class that sets (in initialise()) and restores a context (in terminate()). Use in parallel with a sequence/subtree that does the work while in this context.

Attention

Simply setting a pair of behaviours (set and reset context) on either end of a sequence will not suffice for context switching. In the case that one of the work behaviours in the sequence fails, the final reset context switch will never trigger.

__init__(name='ContextSwitch')[source]

Initialize self. See help(type(self)) for accurate signature.

initialise()[source]

Backup and set a new context.

terminate(new_status)[source]

Restore the context with the previously backed up context.

update()[source]

Just returns RUNNING while it waits for other activities to finish.

py_trees.demos.context_switching.main()[source]

Entry point for the demo script.

py_trees/demos/contex_switching.py
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
#!/usr/bin/env python
#
# License: BSD
#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE
#
##############################################################################
# Documentation
##############################################################################

"""
.. argparse::
   :module: py_trees.demos.context_switching
   :func: command_line_argument_parser
   :prog: py-trees-demo-context-switching

.. graphviz:: dot/demo-context_switching.dot

.. image:: images/context_switching.gif
"""

##############################################################################
# Imports
##############################################################################

import argparse
import py_trees
import sys
import time

import py_trees.console as console

##############################################################################
# Classes
##############################################################################


def description():
    content = "Demonstrates context switching with parallels and sequences.\n"
    content += "\n"
    content += "A context switching behaviour is run in parallel with a work sequence.\n"
    content += "Switching the context occurs in the initialise() and terminate() methods\n"
    content += "of the context switching behaviour. Note that whether the sequence results\n"
    content += "in failure or success, the context switch behaviour will always call the\n"
    content += "terminate() method to restore the context. It will also call terminate()\n"
    content += "to restore the context in the event of a higher priority parent cancelling\n"
    content += "this parallel subtree.\n"
    if py_trees.console.has_colours:
        banner_line = console.green + "*" * 79 + "\n" + console.reset
        s = "\n"
        s += banner_line
        s += console.bold_white + "Context Switching".center(79) + "\n" + console.reset
        s += banner_line
        s += "\n"
        s += content
        s += "\n"
        s += banner_line
    else:
        s = content
    return s


def epilog():
    if py_trees.console.has_colours:
        return console.cyan + "And his noodly appendage reached forth to tickle the blessed...\n" + console.reset
    else:
        return None


def command_line_argument_parser():
    parser = argparse.ArgumentParser(description=description(),
                                     epilog=epilog(),
                                     formatter_class=argparse.RawDescriptionHelpFormatter,
                                     )
    parser.add_argument('-r', '--render', action='store_true', help='render dot tree to file')
    return parser


class ContextSwitch(py_trees.behaviour.Behaviour):
    """
    An example of a context switching class that sets (in ``initialise()``)
    and restores a context (in ``terminate()``). Use in parallel with a
    sequence/subtree that does the work while in this context.

    .. attention:: Simply setting a pair of behaviours (set and reset context) on
        either end of a sequence will not suffice for context switching. In the case
        that one of the work behaviours in the sequence fails, the final reset context
        switch will never trigger.

    """
    def __init__(self, name="ContextSwitch"):
        super(ContextSwitch, self).__init__(name)
        self.feedback_message = "no context"

    def initialise(self):
        """
        Backup and set a new context.
        """
        self.logger.debug("%s.initialise()[switch context]" % (self.__class__.__name__))
        # Some actions that:
        #   1. retrieve the current context from somewhere
        #   2. cache the context internally
        #   3. apply a new context
        self.feedback_message = "new context"

    def update(self):
        """
        Just returns RUNNING while it waits for other activities to finish.
        """
        self.logger.debug("%s.update()[RUNNING][%s]" % (self.__class__.__name__, self.feedback_message))
        return py_trees.common.Status.RUNNING

    def terminate(self, new_status):
        """
        Restore the context with the previously backed up context.
        """
        self.logger.debug("%s.terminate()[%s->%s][restore context]" % (self.__class__.__name__, self.status, new_status))
        # Some actions that:
        #   1. restore the cached context
        self.feedback_message = "restored context"


def create_root():
    root = py_trees.composites.Parallel(name="Parallel", policy=py_trees.common.ParallelPolicy.SuccessOnOne())
    context_switch = ContextSwitch(name="Context")
    sequence = py_trees.composites.Sequence(name="Sequence")
    for job in ["Action 1", "Action 2"]:
        success_after_two = py_trees.behaviours.Count(name=job,
                                                      fail_until=0,
                                                      running_until=2,
                                                      success_until=10)
        sequence.add_child(success_after_two)
    root.add_child(context_switch)
    root.add_child(sequence)
    return root


##############################################################################
# Main
##############################################################################

def main():
    """
    Entry point for the demo script.
    """
    args = command_line_argument_parser().parse_args()
    print(description())
    py_trees.logging.level = py_trees.logging.Level.DEBUG

    root = create_root()

    ####################
    # Rendering
    ####################
    if args.render:
        py_trees.display.render_dot_tree(root)
        sys.exit()

    ####################
    # Execute
    ####################
    root.setup_with_descendants()
    for i in range(1, 6):
        try:
            print("\n--------- Tick {0} ---------\n".format(i))
            root.tick_once()
            print("\n")
            print("{}".format(py_trees.display.ascii_tree(root, show_status=True)))
            time.sleep(1.0)
        except KeyboardInterrupt:
            break
    print("\n")

py-trees-demo-dot-graphs

Renders a dot graph for a simple tree, with blackboxes.

usage: py-trees-demo-dot-graphs [-h]
                                [-l {all,fine_detail,detail,component,big_picture}]

Named Arguments

-l, --level

Possible choices: all, fine_detail, detail, component, big_picture

visibility level

Default: “fine_detail”

digraph demo_dot_graphs_fine_detail {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
"Demo Dot Graphs fine_detail" [fillcolor=cyan, fontcolor=black, fontsize=11, shape=octagon, style=filled];
"BlackBox 1" [fillcolor=gray20, fontcolor=white, fontsize=11, shape=box, style=filled];
"Demo Dot Graphs fine_detail" -> "BlackBox 1";
Worker [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"BlackBox 1" -> Worker;
"Worker*" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"BlackBox 1" -> "Worker*";
"Worker**" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"BlackBox 1" -> "Worker**";
"Blackbox 3" [fillcolor=gray20, fontcolor=dodgerblue, fontsize=11, shape=box, style=filled];
"BlackBox 1" -> "Blackbox 3";
"Worker***" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Blackbox 3" -> "Worker***";
"Worker****" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Blackbox 3" -> "Worker****";
"Worker*****" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Blackbox 3" -> "Worker*****";
"Blackbox 2" [fillcolor=gray20, fontcolor=lawngreen, fontsize=11, shape=box, style=filled];
"Demo Dot Graphs fine_detail" -> "Blackbox 2";
"Worker******" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Blackbox 2" -> "Worker******";
"Worker*******" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Blackbox 2" -> "Worker*******";
"Worker********" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Blackbox 2" -> "Worker********";
}
py_trees.demos.dot_graphs.main()[source]

Entry point for the demo script.

py_trees/demos/dot_graphs.py
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
#!/usr/bin/env python
#
# License: BSD
#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE
#
##############################################################################
# Documentation
##############################################################################

"""
.. argparse::
   :module: py_trees.demos.dot_graphs
   :func: command_line_argument_parser
   :prog: py-trees-demo-dot-graphs

.. graphviz:: dot/demo-dot-graphs.dot

"""

##############################################################################
# Imports
##############################################################################

import argparse
import subprocess
import py_trees

import py_trees.console as console

##############################################################################
# Classes
##############################################################################


def description():
    name = "py-trees-demo-dot-graphs"
    content = "Renders a dot graph for a simple tree, with blackboxes.\n"
    if py_trees.console.has_colours:
        banner_line = console.green + "*" * 79 + "\n" + console.reset
        s = "\n"
        s += banner_line
        s += console.bold_white + "Dot Graphs".center(79) + "\n" + console.reset
        s += banner_line
        s += "\n"
        s += content
        s += "\n"
        s += console.white
        s += console.bold + "    Generate Full Dot Graph" + console.reset + "\n"
        s += "\n"
        s += console.cyan + "        {0}".format(name) + console.reset + "\n"
        s += "\n"
        s += console.bold + "    With Varying Visibility Levels" + console.reset + "\n"
        s += "\n"
        s += console.cyan + "        {0}".format(name) + console.yellow + " --level=all" + console.reset + "\n"
        s += console.cyan + "        {0}".format(name) + console.yellow + " --level=detail" + console.reset + "\n"
        s += console.cyan + "        {0}".format(name) + console.yellow + " --level=component" + console.reset + "\n"
        s += console.cyan + "        {0}".format(name) + console.yellow + " --level=big_picture" + console.reset + "\n"
        s += "\n"
        s += banner_line
    else:
        s = content
    return s


def epilog():
    if py_trees.console.has_colours:
        return console.cyan + "And his noodly appendage reached forth to tickle the blessed...\n" + console.reset
    else:
        return None


def command_line_argument_parser():
    parser = argparse.ArgumentParser(description=description(),
                                     epilog=epilog(),
                                     formatter_class=argparse.RawDescriptionHelpFormatter,
                                     )
    parser.add_argument('-l', '--level', action='store',
                        default='fine_detail',
                        choices=['all', 'fine_detail', 'detail', 'component', 'big_picture'],
                        help='visibility level')
    return parser


def create_tree(level):
    root = py_trees.composites.Selector("Demo Dot Graphs %s" % level)
    first_blackbox = py_trees.composites.Sequence("BlackBox 1")
    first_blackbox.add_child(py_trees.behaviours.Running("Worker"))
    first_blackbox.add_child(py_trees.behaviours.Running("Worker"))
    first_blackbox.add_child(py_trees.behaviours.Running("Worker"))
    first_blackbox.blackbox_level = py_trees.common.BlackBoxLevel.BIG_PICTURE
    second_blackbox = py_trees.composites.Sequence("Blackbox 2")
    second_blackbox.add_child(py_trees.behaviours.Running("Worker"))
    second_blackbox.add_child(py_trees.behaviours.Running("Worker"))
    second_blackbox.add_child(py_trees.behaviours.Running("Worker"))
    second_blackbox.blackbox_level = py_trees.common.BlackBoxLevel.COMPONENT
    third_blackbox = py_trees.composites.Sequence("Blackbox 3")
    third_blackbox.add_child(py_trees.behaviours.Running("Worker"))
    third_blackbox.add_child(py_trees.behaviours.Running("Worker"))
    third_blackbox.add_child(py_trees.behaviours.Running("Worker"))
    third_blackbox.blackbox_level = py_trees.common.BlackBoxLevel.DETAIL
    root.add_child(first_blackbox)
    root.add_child(second_blackbox)
    first_blackbox.add_child(third_blackbox)
    return root


##############################################################################
# Main
##############################################################################

def main():
    """
    Entry point for the demo script.
    """
    args = command_line_argument_parser().parse_args()
    args.enum_level = py_trees.common.string_to_visibility_level(args.level)
    print(description())
    py_trees.logging.level = py_trees.logging.Level.DEBUG

    root = create_tree(args.level)
    py_trees.display.render_dot_tree(root, args.enum_level)

    if py_trees.utilities.which("xdot"):
        try:
            subprocess.call(["xdot", "demo_dot_graphs_%s.dot" % args.level])
        except KeyboardInterrupt:
            pass
    else:
        print("")
        console.logerror("No xdot viewer found, skipping display [hint: sudo apt install xdot]")
        print("")

py-trees-demo-logging

A demonstration of tree stewardship.

A slightly less trivial tree that uses a simple stdout pre-tick handler and both the debug and snapshot visitors for logging and displaying the state of the tree.

EVENTS

  • 3 : sequence switches from running to success
  • 4 : selector’s first child flicks to success once only
  • 8 : the fallback idler kicks in as everything else fails
  • 14 : the first child kicks in again, aborting a running sequence behind it

usage: py-trees-demo-tree-stewardship [-h] [-r | -i]

Named Arguments

-r, --render

render dot tree to file

Default: False

-i, --interactive
 

pause and wait for keypress at each tick

Default: False

digraph demo_tree {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
"Demo Tree" [fillcolor=cyan, fontcolor=black, fontsize=11, shape=octagon, style=filled];
EveryN [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Demo Tree" -> EveryN;
Sequence [fillcolor=gray20, fontcolor=lawngreen, fontsize=11, shape=box, style=filled];
"Demo Tree" -> Sequence;
Guard [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Guard;
Periodic [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Periodic;
Finisher [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Finisher;
Idle [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Demo Tree" -> Idle;
}
_images/tree_stewardship.gif
py_trees.demos.logging.display_ascii_tree(snapshot_visitor, behaviour_tree)[source]

Prints an ascii tree with the current snapshot status.

py_trees.demos.logging.logger(winds_of_change_visitor, behaviour_tree)[source]

A post-tick handler that logs the tree (relevant parts thereof) to a yaml file.

py_trees.demos.logging.main()[source]

Entry point for the demo script.

py_trees/demos/logging.py
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
#!/usr/bin/env python
#
# License: BSD
#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE
#
##############################################################################
# Documentation
##############################################################################

"""
.. argparse::
   :module: py_trees.demos.stewardship
   :func: command_line_argument_parser
   :prog: py-trees-demo-tree-stewardship

.. graphviz:: dot/stewardship.dot

.. image:: images/tree_stewardship.gif
"""

##############################################################################
# Imports
##############################################################################

import argparse
import functools
import json
import py_trees
import sys
import time

import py_trees.console as console

##############################################################################
# Classes
##############################################################################


def description(root):
    content = "A demonstration of logging with trees.\n\n"
    content += "This demo utilises a WindsOfChange visitor to trigger\n"
    content += "a post-tick handler to dump a serialisation of the\n"
    content += "tree to a json log file.\n"
    content += "\n"
    content += "This coupling of visitor and post-tick handler can be\n"
    content += "used for any kind of event handling - the visitor is the\n"
    content += "trigger and the post-tick handler the action. Aside from\n"
    content += "logging, the most common use case is to serialise the tree\n"
    content += "for messaging to a graphical, runtime monitor.\n"
    content += "\n"
    if py_trees.console.has_colours:
        banner_line = console.green + "*" * 79 + "\n" + console.reset
        s = "\n"
        s += banner_line
        s += console.bold_white + "Logging".center(79) + "\n" + console.reset
        s += banner_line
        s += "\n"
        s += content
        s += "\n"
        s += banner_line
    else:
        s = content
    return s


def epilog():
    if py_trees.console.has_colours:
        return console.cyan + "And his noodly appendage reached forth to tickle the blessed...\n" + console.reset
    else:
        return None


def command_line_argument_parser():
    parser = argparse.ArgumentParser(description=description(create_tree()),
                                     epilog=epilog(),
                                     formatter_class=argparse.RawDescriptionHelpFormatter,
                                     )
    group = parser.add_mutually_exclusive_group()
    group.add_argument('-r', '--render', action='store_true', help='render dot tree to file')
    group.add_argument('-i', '--interactive', action='store_true', help='pause and wait for keypress at each tick')
    return parser


def logger(winds_of_change_visitor, behaviour_tree):
    """
    A post-tick handler that logs the tree (relevant parts thereof) to a yaml file.
    """
    if winds_of_change_visitor.changed:
        print(console.cyan + "Logging.......................yes\n" + console.reset)
        tree_serialisation = {
            'tick': behaviour_tree.count,
            'nodes': []
        }
        for node in behaviour_tree.root.iterate():
            node_type_str = "Behaviour"
            for behaviour_type in [py_trees.composites.Sequence,
                                   py_trees.composites.Selector,
                                   py_trees.composites.Parallel,
                                   py_trees.decorators.Decorator]:
                if isinstance(node, behaviour_type):
                    node_type_str = behaviour_type.__name__
            node_snapshot = {
                'name': node.name,
                'id': str(node.id),
                'parent_id': str(node.parent.id) if node.parent else "none",
                'child_ids': [str(child.id) for child in node.children],
                'tip_id': str(node.tip().id) if node.tip() else 'none',
                'class_name': str(node.__module__) + '.' + str(type(node).__name__),
                'type': node_type_str,
                'status': node.status.value,
                'message': node.feedback_message,
                'is_active': True if node.id in winds_of_change_visitor.ticked_nodes else False
                }
            tree_serialisation['nodes'].append(node_snapshot)
        if behaviour_tree.count == 0:
            with open('dump.json', 'w+') as outfile:
                json.dump(tree_serialisation, outfile, indent=4)
        else:
            with open('dump.json', 'a') as outfile:
                json.dump(tree_serialisation, outfile, indent=4)
    else:
        print(console.yellow + "Logging.......................no\n" + console.reset)


def display_ascii_tree(snapshot_visitor, behaviour_tree):
    """
    Prints an ascii tree with the current snapshot status.
    """
    print("\n" + py_trees.display.ascii_tree(
        behaviour_tree.root,
        visited=snapshot_visitor.visited,
        previously_visited=snapshot_visitor.previously_visited)
    )


def create_tree():
    every_n_success = py_trees.behaviours.SuccessEveryN("EveryN", 5)
    sequence = py_trees.composites.Sequence(name="Sequence")
    guard = py_trees.behaviours.Success("Guard")
    periodic_success = py_trees.behaviours.Periodic("Periodic", 3)
    finisher = py_trees.behaviours.Success("Finisher")
    sequence.add_child(guard)
    sequence.add_child(periodic_success)
    sequence.add_child(finisher)
    sequence.blackbox_level = py_trees.common.BlackBoxLevel.COMPONENT
    idle = py_trees.behaviours.Success("Idle")
    root = py_trees.composites.Selector(name="Logging")
    root.add_child(every_n_success)
    root.add_child(sequence)
    root.add_child(idle)
    return root


##############################################################################
# Main
##############################################################################

def main():
    """
    Entry point for the demo script.
    """
    args = command_line_argument_parser().parse_args()
    py_trees.logging.level = py_trees.logging.Level.DEBUG
    tree = create_tree()
    print(description(tree))

    ####################
    # Rendering
    ####################
    if args.render:
        py_trees.display.render_dot_tree(tree)
        sys.exit()

    ####################
    # Tree Stewardship
    ####################
    behaviour_tree = py_trees.trees.BehaviourTree(tree)

    debug_visitor = py_trees.visitors.DebugVisitor()
    snapshot_visitor = py_trees.visitors.SnapshotVisitor()
    winds_of_change_visitor = py_trees.visitors.WindsOfChangeVisitor()

    behaviour_tree.visitors.append(debug_visitor)
    behaviour_tree.visitors.append(snapshot_visitor)
    behaviour_tree.visitors.append(winds_of_change_visitor)

    behaviour_tree.add_post_tick_handler(functools.partial(display_ascii_tree, snapshot_visitor))
    behaviour_tree.add_post_tick_handler(functools.partial(logger, winds_of_change_visitor))

    behaviour_tree.setup(timeout=15)

    ####################
    # Tick Tock
    ####################
    if args.interactive:
        py_trees.console.read_single_keypress()
    while True:
        try:
            behaviour_tree.tick()
            if args.interactive:
                py_trees.console.read_single_keypress()
            else:
                time.sleep(0.5)
        except KeyboardInterrupt:
            break
    print("\n")

py-trees-demo-selector

Higher priority switching and interruption in the children of a selector.

In this example the higher priority child is setup to fail initially, falling back to the continually running second child. On the third tick, the first child succeeds and cancels the hitherto running child.

usage: py-trees-demo-selector [-h] [-r]

Named Arguments

-r, --render

render dot tree to file

Default: False

digraph selector {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Selector [fillcolor=cyan, fontcolor=black, fontsize=11, shape=octagon, style=filled];
"After Two" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Selector -> "After Two";
Running [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Selector -> Running;
}
_images/selector.gif
py_trees.demos.selector.main()[source]

Entry point for the demo script.

py_trees/demos/selector.py
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
#!/usr/bin/env python
#
# License: BSD
#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE
#
##############################################################################
# Documentation
##############################################################################

"""
.. argparse::
   :module: py_trees.demos.selector
   :func: command_line_argument_parser
   :prog: py-trees-demo-selector

.. graphviz:: dot/demo-selector.dot

.. image:: images/selector.gif

"""
##############################################################################
# Imports
##############################################################################

import argparse
import py_trees
import sys
import time

import py_trees.console as console

##############################################################################
# Classes
##############################################################################


def description():
    content = "Higher priority switching and interruption in the children of a selector.\n"
    content += "\n"
    content += "In this example the higher priority child is setup to fail initially,\n"
    content += "falling back to the continually running second child. On the third\n"
    content += "tick, the first child succeeds and cancels the hitherto running child.\n"
    if py_trees.console.has_colours:
        banner_line = console.green + "*" * 79 + "\n" + console.reset
        s = "\n"
        s += banner_line
        s += console.bold_white + "Selectors".center(79) + "\n" + console.reset
        s += banner_line
        s += "\n"
        s += content
        s += "\n"
        s += banner_line
    else:
        s = content
    return s


def epilog():
    if py_trees.console.has_colours:
        return console.cyan + "And his noodly appendage reached forth to tickle the blessed...\n" + console.reset
    else:
        return None


def command_line_argument_parser():
    parser = argparse.ArgumentParser(description=description(),
                                     epilog=epilog(),
                                     formatter_class=argparse.RawDescriptionHelpFormatter,
                                     )
    parser.add_argument('-r', '--render', action='store_true', help='render dot tree to file')
    return parser


def create_root():
    root = py_trees.composites.Selector("Selector")
    success_after_two = py_trees.behaviours.Count(name="After Two",
                                                  fail_until=2,
                                                  running_until=2,
                                                  success_until=10)
    always_running = py_trees.behaviours.Running(name="Running")
    root.add_children([success_after_two, always_running])
    return root


##############################################################################
# Main
##############################################################################

def main():
    """
    Entry point for the demo script.
    """
    args = command_line_argument_parser().parse_args()
    print(description())
    py_trees.logging.level = py_trees.logging.Level.DEBUG

    root = create_root()

    ####################
    # Rendering
    ####################
    if args.render:
        py_trees.display.render_dot_tree(root)
        sys.exit()

    ####################
    # Execute
    ####################
    root.setup_with_descendants()
    for i in range(1, 4):
        try:
            print("\n--------- Tick {0} ---------\n".format(i))
            root.tick_once()
            print("\n")
            print(py_trees.display.ascii_tree(root=root, show_status=True))
            time.sleep(1.0)
        except KeyboardInterrupt:
            break
    print("\n")

py-trees-demo-sequence

Demonstrates sequences in action.

A sequence is populated with 2-tick jobs that are allowed to run through to completion.

usage: py-trees-demo-sequence [-h] [-r]

Named Arguments

-r, --render

render dot tree to file

Default: False

digraph sequence {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Sequence [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
"Job 1" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Job 1";
"Job 2" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Job 2";
"Job 3" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Job 3";
}
_images/sequence.gif
py_trees.demos.sequence.main()[source]

Entry point for the demo script.

py_trees/demos/sequence.py
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
#!/usr/bin/env python
#
# License: BSD
#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE
#
##############################################################################
# Documentation
##############################################################################

"""
.. argparse::
   :module: py_trees.demos.sequence
   :func: command_line_argument_parser
   :prog: py-trees-demo-sequence

.. graphviz:: dot/demo-sequence.dot

.. image:: images/sequence.gif
"""

##############################################################################
# Imports
##############################################################################

import argparse
import py_trees
import sys
import time

import py_trees.console as console

##############################################################################
# Classes
##############################################################################


def description():
    content = "Demonstrates sequences in action.\n\n"
    content += "A sequence is populated with 2-tick jobs that are allowed to run through to\n"
    content += "completion.\n"

    if py_trees.console.has_colours:
        banner_line = console.green + "*" * 79 + "\n" + console.reset
        s = "\n"
        s += banner_line
        s += console.bold_white + "Sequences".center(79) + "\n" + console.reset
        s += banner_line
        s += "\n"
        s += content
        s += "\n"
        s += banner_line
    else:
        s = content
    return s


def epilog():
    if py_trees.console.has_colours:
        return console.cyan + "And his noodly appendage reached forth to tickle the blessed...\n" + console.reset
    else:
        return None


def command_line_argument_parser():
    parser = argparse.ArgumentParser(description=description(),
                                     epilog=epilog(),
                                     formatter_class=argparse.RawDescriptionHelpFormatter,
                                     )
    parser.add_argument('-r', '--render', action='store_true', help='render dot tree to file')
    return parser


def create_root():
    root = py_trees.composites.Sequence("Sequence")
    for action in ["Action 1", "Action 2", "Action 3"]:
        success_after_two = py_trees.behaviours.Count(name=action,
                                                      fail_until=0,
                                                      running_until=1,
                                                      success_until=10)
        root.add_child(success_after_two)
    return root


##############################################################################
# Main
##############################################################################

def main():
    """
    Entry point for the demo script.
    """
    args = command_line_argument_parser().parse_args()
    print(description())
    py_trees.logging.level = py_trees.logging.Level.DEBUG

    root = create_root()

    ####################
    # Rendering
    ####################
    if args.render:
        py_trees.display.render_dot_tree(root)
        sys.exit()

    ####################
    # Execute
    ####################
    root.setup_with_descendants()
    for i in range(1, 6):
        try:
            print("\n--------- Tick {0} ---------\n".format(i))
            root.tick_once()
            print("\n")
            print(py_trees.display.ascii_tree(root=root, show_status=True))
            time.sleep(1.0)
        except KeyboardInterrupt:
            break
    print("\n")

py-trees-demo-tree-stewardship

A demonstration of tree stewardship.

A slightly less trivial tree that uses a simple stdout pre-tick handler and both the debug and snapshot visitors for logging and displaying the state of the tree.

EVENTS

  • 3 : sequence switches from running to success
  • 4 : selector’s first child flicks to success once only
  • 8 : the fallback idler kicks in as everything else fails
  • 14 : the first child kicks in again, aborting a running sequence behind it

usage: py-trees-demo-tree-stewardship [-h] [-r | -i]

Named Arguments

-r, --render

render dot tree to file

Default: False

-i, --interactive
 

pause and wait for keypress at each tick

Default: False

digraph demo_tree {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
"Demo Tree" [fillcolor=cyan, fontcolor=black, fontsize=11, shape=octagon, style=filled];
EveryN [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Demo Tree" -> EveryN;
Sequence [fillcolor=gray20, fontcolor=lawngreen, fontsize=11, shape=box, style=filled];
"Demo Tree" -> Sequence;
Guard [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Guard;
Periodic [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Periodic;
Finisher [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Finisher;
Idle [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Demo Tree" -> Idle;
}
_images/tree_stewardship.gif
py_trees.demos.stewardship.main()[source]

Entry point for the demo script.

py_trees.demos.stewardship.post_tick_handler(snapshot_visitor, behaviour_tree)[source]

Prints an ascii tree with the current snapshot status.

py_trees.demos.stewardship.pre_tick_handler(behaviour_tree)[source]

This prints a banner and will run immediately before every tick of the tree.

Parameters:behaviour_tree (BehaviourTree) – the tree custodian
py_trees/demos/stewardship.py
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
#!/usr/bin/env python
#
# License: BSD
#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE
#
##############################################################################
# Documentation
##############################################################################

"""
.. argparse::
   :module: py_trees.demos.stewardship
   :func: command_line_argument_parser
   :prog: py-trees-demo-tree-stewardship

.. graphviz:: dot/stewardship.dot

.. image:: images/tree_stewardship.gif
"""

##############################################################################
# Imports
##############################################################################

import argparse
import functools
import py_trees
import sys
import time

import py_trees.console as console

##############################################################################
# Classes
##############################################################################


def description(root):
    content = "A demonstration of tree stewardship.\n\n"
    content += "A slightly less trivial tree that uses a simple stdout pre-tick handler\n"
    content += "and both the debug and snapshot visitors for logging and displaying\n"
    content += "the state of the tree.\n"
    content += "\n"
    content += "EVENTS\n"
    content += "\n"
    content += " -  3 : sequence switches from running to success\n"
    content += " -  4 : selector's first child flicks to success once only\n"
    content += " -  8 : the fallback idler kicks in as everything else fails\n"
    content += " - 14 : the first child kicks in again, aborting a running sequence behind it\n"
    content += "\n"
    if py_trees.console.has_colours:
        banner_line = console.green + "*" * 79 + "\n" + console.reset
        s = "\n"
        s += banner_line
        s += console.bold_white + "Trees".center(79) + "\n" + console.reset
        s += banner_line
        s += "\n"
        s += content
        s += "\n"
        s += banner_line
    else:
        s = content
    return s


def epilog():
    if py_trees.console.has_colours:
        return console.cyan + "And his noodly appendage reached forth to tickle the blessed...\n" + console.reset
    else:
        return None


def command_line_argument_parser():
    parser = argparse.ArgumentParser(description=description(create_tree()),
                                     epilog=epilog(),
                                     formatter_class=argparse.RawDescriptionHelpFormatter,
                                     )
    group = parser.add_mutually_exclusive_group()
    group.add_argument('-r', '--render', action='store_true', help='render dot tree to file')
    group.add_argument('-i', '--interactive', action='store_true', help='pause and wait for keypress at each tick')
    return parser


def pre_tick_handler(behaviour_tree):
    """
    This prints a banner and will run immediately before every tick of the tree.

    Args:
        behaviour_tree (:class:`~py_trees.trees.BehaviourTree`): the tree custodian

    """
    print("\n--------- Run %s ---------\n" % behaviour_tree.count)


def post_tick_handler(snapshot_visitor, behaviour_tree):
    """
    Prints an ascii tree with the current snapshot status.
    """
    print("\n" + py_trees.display.ascii_tree(
        root=behaviour_tree.root,
        visited=snapshot_visitor.visited,
        previously_visited=snapshot_visitor.visited)
    )


def create_tree():
    every_n_success = py_trees.behaviours.SuccessEveryN("EveryN", 5)
    sequence = py_trees.composites.Sequence(name="Sequence")
    guard = py_trees.behaviours.Success("Guard")
    periodic_success = py_trees.behaviours.Periodic("Periodic", 3)
    finisher = py_trees.behaviours.Success("Finisher")
    sequence.add_child(guard)
    sequence.add_child(periodic_success)
    sequence.add_child(finisher)
    sequence.blackbox_level = py_trees.common.BlackBoxLevel.COMPONENT
    idle = py_trees.behaviours.Success("Idle")
    root = py_trees.composites.Selector(name="Demo Tree")
    root.add_child(every_n_success)
    root.add_child(sequence)
    root.add_child(idle)
    return root


##############################################################################
# Main
##############################################################################

def main():
    """
    Entry point for the demo script.
    """
    args = command_line_argument_parser().parse_args()
    py_trees.logging.level = py_trees.logging.Level.DEBUG
    tree = create_tree()
    print(description(tree))

    ####################
    # Rendering
    ####################
    if args.render:
        py_trees.display.render_dot_tree(tree)
        sys.exit()

    ####################
    # Tree Stewardship
    ####################
    behaviour_tree = py_trees.trees.BehaviourTree(tree)
    behaviour_tree.add_pre_tick_handler(pre_tick_handler)
    behaviour_tree.visitors.append(py_trees.visitors.DebugVisitor())
    snapshot_visitor = py_trees.visitors.SnapshotVisitor()
    behaviour_tree.add_post_tick_handler(functools.partial(post_tick_handler, snapshot_visitor))
    behaviour_tree.visitors.append(snapshot_visitor)
    behaviour_tree.setup(timeout=15)

    ####################
    # Tick Tock
    ####################
    if args.interactive:
        py_trees.console.read_single_keypress()
    while True:
        try:
            behaviour_tree.tick()
            if args.interactive:
                py_trees.console.read_single_keypress()
            else:
                time.sleep(0.5)
        except KeyboardInterrupt:
            break
    print("\n")

py-trees-demo-pick-up-where-you-left-off

A demonstration of the ‘pick up where you left off’ idiom.

A common behaviour tree pattern that allows you to resume work after being interrupted by a high priority interrupt.

EVENTS

  • 2 : task one done, task two running
  • 3 : high priority interrupt
  • 7 : task two restarts
  • 9 : task two done

usage: py-trees-demo-pick-up-where-you-left-off [-h] [-r | -i]

Named Arguments

-r, --render

render dot tree to file

Default: False

-i, --interactive
 

pause and wait for keypress at each tick

Default: False

digraph pick_up_where_you_left_off {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
"Pick Up Where You Left Off" [shape=octagon, style=filled, fillcolor=cyan, fontsize=11, fontcolor=black];
"High Priority" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Pick Up Where You Left Off" -> "High Priority";
Tasks [shape=box, style=filled, fillcolor=orange, fontsize=11, fontcolor=black];
"Pick Up Where You Left Off" -> Tasks;
"Do or Don't" [shape=octagon, style=filled, fillcolor=cyan, fontsize=11, fontcolor=black];
Tasks -> "Do or Don't";
"Done?" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Do or Don't" -> "Done?";
Worker [shape=box, style=filled, fillcolor=orange, fontsize=11, fontcolor=black];
"Do or Don't" -> Worker;
"Task 1" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Worker -> "Task 1";
"Mark\ntask_1_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Worker -> "Mark\ntask_1_done";
"Do or Don't*" [shape=octagon, style=filled, fillcolor=cyan, fontsize=11, fontcolor=black];
Tasks -> "Do or Don't*";
"Done?*" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Do or Don't*" -> "Done?*";
"Worker*" [shape=box, style=filled, fillcolor=orange, fontsize=11, fontcolor=black];
"Do or Don't*" -> "Worker*";
"Task 2" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Worker*" -> "Task 2";
"Mark\ntask_2_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Worker*" -> "Mark\ntask_2_done";
"Clear\ntask_1_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Tasks -> "Clear\ntask_1_done";
"Clear\ntask_2_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Tasks -> "Clear\ntask_2_done";
}
_images/pick_up_where_you_left_off.gif
py_trees.demos.pick_up_where_you_left_off.main()[source]

Entry point for the demo script.

py_trees.demos.pick_up_where_you_left_off.post_tick_handler(snapshot_visitor, behaviour_tree)[source]

Prints an ascii tree with the current snapshot status.

py_trees.demos.pick_up_where_you_left_off.pre_tick_handler(behaviour_tree)[source]

This prints a banner and will run immediately before every tick of the tree.

Parameters:behaviour_tree (BehaviourTree) – the tree custodian
py_trees/demos/pick_up_where_you_left_off.py
  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
#!/usr/bin/env python
#
# License: BSD
#   https://raw.githubusercontent.com/splintered-reality/py_trees/devel/LICENSE
#
##############################################################################
# Documentation
##############################################################################

"""
.. argparse::
   :module: py_trees.demos.pick_up_where_you_left_off
   :func: command_line_argument_parser
   :prog: py-trees-demo-pick-up-where-you-left-off

.. graphviz:: dot/pick_up_where_you_left_off.dot

.. image:: images/pick_up_where_you_left_off.gif
"""

##############################################################################
# Imports
##############################################################################

import argparse
import functools
import py_trees
import sys
import time

import py_trees.console as console

##############################################################################
# Classes
##############################################################################


def description(root):
    content = "A demonstration of the 'pick up where you left off' idiom.\n\n"
    content += "A common behaviour tree pattern that allows you to resume\n"
    content += "work after being interrupted by a high priority interrupt.\n"
    content += "\n"
    content += "EVENTS\n"
    content += "\n"
    content += " -  2 : task one done, task two running\n"
    content += " -  3 : high priority interrupt\n"
    content += " -  7 : task two restarts\n"
    content += " -  9 : task two done\n"
    content += "\n"
    if py_trees.console.has_colours:
        banner_line = console.green + "*" * 79 + "\n" + console.reset
        s = "\n"
        s += banner_line
        s += console.bold_white + "Trees".center(79) + "\n" + console.reset
        s += banner_line
        s += "\n"
        s += content
        s += "\n"
        s += banner_line
    else:
        s = content
    return s


def epilog():
    if py_trees.console.has_colours:
        return console.cyan + "And his noodly appendage reached forth to tickle the blessed...\n" + console.reset
    else:
        return None


def command_line_argument_parser():
    parser = argparse.ArgumentParser(description=description(create_root()),
                                     epilog=epilog(),
                                     formatter_class=argparse.RawDescriptionHelpFormatter,
                                     )
    group = parser.add_mutually_exclusive_group()
    group.add_argument('-r', '--render', action='store_true', help='render dot tree to file')
    group.add_argument('-i', '--interactive', action='store_true', help='pause and wait for keypress at each tick')
    return parser


def pre_tick_handler(behaviour_tree):
    """
    This prints a banner and will run immediately before every tick of the tree.

    Args:
        behaviour_tree (:class:`~py_trees.trees.BehaviourTree`): the tree custodian

    """
    print("\n--------- Run %s ---------\n" % behaviour_tree.count)


def post_tick_handler(snapshot_visitor, behaviour_tree):
    """
    Prints an ascii tree with the current snapshot status.
    """
    print(
        "\n" + py_trees.display.ascii_tree(
            root=behaviour_tree.root,
            visited=snapshot_visitor.visited,
            previously_visited=snapshot_visitor.previously_visited
        )
    )


def create_root():
    task_one = py_trees.behaviours.Count(
        name="Task 1",
        fail_until=0,
        running_until=2,
        success_until=10
    )
    task_two = py_trees.behaviours.Count(
        name="Task 2",
        fail_until=0,
        running_until=2,
        success_until=10
    )
    high_priority_interrupt = py_trees.decorators.RunningIsFailure(
        child=py_trees.behaviours.Periodic(
            name="High Priority",
            n=3
        )
    )
    piwylo = py_trees.idioms.pick_up_where_you_left_off(
        name="Pick Up\nWhere You\nLeft Off",
        tasks=[task_one, task_two]
    )
    root = py_trees.composites.Selector(name="Root")
    root.add_children([high_priority_interrupt, piwylo])

    return root

##############################################################################
# Main
##############################################################################


def main():
    """
    Entry point for the demo script.
    """
    args = command_line_argument_parser().parse_args()
    py_trees.logging.level = py_trees.logging.Level.DEBUG
    root = create_root()
    print(description(root))

    ####################
    # Rendering
    ####################
    if args.render:
        py_trees.display.render_dot_tree(root)
        sys.exit()

    ####################
    # Tree Stewardship
    ####################
    behaviour_tree = py_trees.trees.BehaviourTree(root)
    behaviour_tree.add_pre_tick_handler(pre_tick_handler)
    behaviour_tree.visitors.append(py_trees.visitors.DebugVisitor())
    snapshot_visitor = py_trees.visitors.SnapshotVisitor()
    behaviour_tree.add_post_tick_handler(functools.partial(post_tick_handler, snapshot_visitor))
    behaviour_tree.visitors.append(snapshot_visitor)
    behaviour_tree.setup(timeout=15)

    ####################
    # Tick Tock
    ####################
    if args.interactive:
        py_trees.console.read_single_keypress()
    for unused_i in range(1, 11):
        try:
            behaviour_tree.tick()
            if args.interactive:
                py_trees.console.read_single_keypress()
            else:
                time.sleep(0.5)
        except KeyboardInterrupt:
            break
    print("\n")

Programs

py-trees-render

Point this program at a method which creates a root to render to dot/svg/png.

Examples

$ py-trees-render py_trees.demos.stewardship.create_tree
$ py-trees-render --name=foo py_trees.demos.stewardship.create_tree
$ py-trees-render --kwargs='{"level":"all"}' py_trees.demos.dot_graphs.create_tree

usage: py-trees-render [-h]
                       [-l {all,fine_detail,detail,component,big_picture}]
                       [-n NAME] [-k KWARGS] [-v]
                       method

Positional Arguments

method space separated list of blackboard variables to watch

Named Arguments

-l, --level

Possible choices: all, fine_detail, detail, component, big_picture

visibility level

Default: “fine_detail”

-n, --name name to use for the created files (defaults to the root behaviour name)
-k, --kwargs

dictionary of keyword arguments to the method

Default: {}

-v, --verbose

embellish each node in the dot graph with extra information

Default: False

_images/render.gif

Module API

py_trees

This is the top-level namespace of the py_trees package.

py_trees.behaviour

The core behaviour template. All behaviours, standalone and composite, inherit from this class.

class py_trees.behaviour.Behaviour(name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Bases: object

Defines the basic properties and methods required of a node in a behaviour tree. When implementing your own behaviour, subclass this class.

Parameters:

name (str, optional) – the behaviour name, defaults to auto-generating from the class name

Raises:

TypeError – if the provided name is not a string

Variables:
  • id (uuid.UUID) – automagically generated unique identifier for the behaviour
  • name (str) – the behaviour name
  • status (Status) – the behaviour status (INVALID, RUNNING, FAILURE, SUCCESS)
  • parent (Behaviour) – a Composite instance if nested in a tree, otherwise None
  • children ([Behaviour]) – empty for regular behaviours, populated for composites
  • logger (logging.Logger) – a simple logging mechanism
  • feedback_message (str) – a simple message used to notify of significant happenings
  • blackbox_level (BlackBoxLevel) – a helper variable for dot graphs and runtime gui’s to collapse/explode entire subtrees dependent upon the blackbox level.
has_parent_with_instance_type(instance_type)[source]

Moves up through this behaviour’s parents looking for a behaviour with the same instance type as that specified.

Parameters:instance_type (str) – instance type of the parent to match
Returns:whether a parent was found or not
Return type:bool
has_parent_with_name(name)[source]

Searches through this behaviour’s parents, and their parents, looking for a behaviour with the same name as that specified.

Parameters:name (str) – name of the parent to match, can be a regular expression
Returns:whether a parent was found or not
Return type:bool
initialise()[source]

Note

User Customisable Callback

Subclasses may override this method to perform any necessary initialising/clearing/resetting of variables when when preparing to enter this behaviour if it was not previously RUNNING. i.e. Expect this to trigger more than once!

iterate(direct_descendants=False)[source]

Generator that provides iteration over this behaviour and all its children. To traverse the entire tree:

for node in my_behaviour.iterate():
    print("Name: {0}".format(node.name))
Parameters:direct_descendants (bool) – only yield children one step away from this behaviour.
Yields:Behaviour – one of it’s children
setup(**kwargs)[source]

Note

User Customisable Callback

Subclasses may override this method for any one-off delayed construction & validation that is necessary prior to ticking the tree. Such construction is best done here rather than in __init__ so that trees can be instantiated on the fly for easy rendering to dot graphs without imposing runtime requirements (e.g. establishing a middleware connection to a sensor or a driver to a serial port).

Equally as important, executing methods which validate the configuration of behaviours will increase confidence that your tree will successfully tick without logical software errors before actually ticking. This is useful both before a tree’s first tick and immediately after any modifications to a tree has been made between ticks.

Tip

Faults are notified to the user of the behaviour via exceptions. Choice of exception to use is left to the user.

Warning

The kwargs argument is for distributing objects at runtime to behaviours before ticking. For example, a simulator instance with which behaviours can interact with the simulator’s python api, a ros2 node for setting up communications. Use sparingly, as this is not proof against keyword conflicts amongst disparate libraries of behaviours.

Parameters:**kwargs (dict) – distribute arguments to this behaviour and in turn, all of it’s children
Raises:Exception – if this behaviour has a fault in construction or configuration
setup_with_descendants()[source]

Iterates over this child, it’s children (it’s children’s children, …) calling the user defined setup() on each in turn.

stop(new_status=<Status.INVALID: 'INVALID'>)[source]
Parameters:new_status (Status) – the behaviour is transitioning to this new status

This calls the user defined terminate() method and also resets the generator. It will finally set the new status once the user’s terminate() function has been called.

Warning

Override this method only in exceptional circumstances, prefer overriding terminate() instead.

terminate(new_status)[source]

Note

User Customisable Callback

Subclasses may override this method to clean up. It will be triggered when a behaviour either finishes execution (switching from RUNNING to FAILURE || SUCCESS) or it got interrupted by a higher priority branch (switching to INVALID). Remember that the initialise() method will handle resetting of variables before re-entry, so this method is about disabling resources until this behaviour’s next tick. This could be a indeterminably long time. e.g.

  • cancel an external action that got started
  • shut down any tempoarary communication handles
Parameters:new_status (Status) – the behaviour is transitioning to this new status

Warning

Do not set self.status = new_status here, that is automatically handled by the stop() method. Use the argument purely for introspection purposes (e.g. comparing the current state in self.status with the state it will transition to in new_status.

tick()[source]

This function is a generator that can be used by an iterator on an entire behaviour tree. It handles the logic for deciding when to call the user’s initialise() and terminate() methods as well as making the actual call to the user’s update() method that determines the behaviour’s new status once the tick has finished. Once done, it will then yield itself (generator mechanism) so that it can be used as part of an iterator for the entire tree.

for node in my_behaviour.tick():
    print("Do something")

Note

This is a generator function, you must use this with yield. If you need a direct call, prefer tick_once() instead.

Yields:Behaviour – a reference to itself

Warning

Override this method only in exceptional circumstances, prefer overriding update() instead.

tick_once()[source]

A direct means of calling tick on this object without using the generator mechanism.

tip()[source]

Get the tip of this behaviour’s subtree (if it has one) after it’s last tick. This corresponds to the the deepest node that was running before the subtree traversal reversed direction and headed back to this node.

Returns:child behaviour, itself or None if its status is INVALID
Return type:Behaviour or None
update()[source]

Note

User Customisable Callback

Returns:the behaviour’s new status Status
Return type:Status

Subclasses may override this method to perform any logic required to arrive at a decision on the behaviour’s new status. It is the primary worker function called on by the tick() mechanism.

Tip

This method should be almost instantaneous and non-blocking

verbose_info_string()[source]

Override to provide a one line informative string about the behaviour. This gets used in, e.g. dot graph rendering of the tree.

Tip

Use this sparingly. A good use case is for when the behaviour type and class name isn’t sufficient to inform the user about it’s mechanisms for controlling the flow of a tree tick (e.g. parallels with policies).

visit(visitor)[source]

This is functionality that enables external introspection into the behaviour. It gets used by the tree manager classes to collect information as ticking traverses a tree.

Parameters:visitor (object) – the visiting class, must have a run(Behaviour) method.

py_trees.behaviours

A library of fundamental behaviours for use.

class py_trees.behaviours.Count(name='Count', fail_until=3, running_until=5, success_until=6, reset=True)[source]

Bases: py_trees.behaviour.Behaviour

A counting behaviour that updates its status at each tick depending on the value of the counter. The status will move through the states in order - FAILURE, RUNNING, SUCCESS.

This behaviour is useful for simple testing and demo scenarios.

Parameters:
  • name (str) – name of the behaviour
  • fail_until (int) – set status to FAILURE until the counter reaches this value
  • running_until (int) – set status to RUNNING until the counter reaches this value
  • success_until (int) – set status to SUCCESS until the counter reaches this value
  • reset (bool) – whenever invalidated (usually by a sequence reinitialising, or higher priority interrupting)
Variables:

count (int) – a simple counter which increments every tick

terminate(new_status)[source]

Note

User Customisable Callback

Subclasses may override this method to clean up. It will be triggered when a behaviour either finishes execution (switching from RUNNING to FAILURE || SUCCESS) or it got interrupted by a higher priority branch (switching to INVALID). Remember that the initialise() method will handle resetting of variables before re-entry, so this method is about disabling resources until this behaviour’s next tick. This could be a indeterminably long time. e.g.

  • cancel an external action that got started
  • shut down any tempoarary communication handles
Parameters:new_status (Status) – the behaviour is transitioning to this new status

Warning

Do not set self.status = new_status here, that is automatically handled by the stop() method. Use the argument purely for introspection purposes (e.g. comparing the current state in self.status with the state it will transition to in new_status.

update()[source]

Note

User Customisable Callback

Returns:the behaviour’s new status Status
Return type:Status

Subclasses may override this method to perform any logic required to arrive at a decision on the behaviour’s new status. It is the primary worker function called on by the tick() mechanism.

Tip

This method should be almost instantaneous and non-blocking

class py_trees.behaviours.Dummy(name='Dummy')

Bases: py_trees.behaviour.Behaviour

class py_trees.behaviours.Failure(name='Failure')

Bases: py_trees.behaviour.Behaviour

class py_trees.behaviours.Periodic(name, n)[source]

Bases: py_trees.behaviour.Behaviour

Simply periodically rotates it’s status over the RUNNING, SUCCESS, FAILURE states. That is, RUNNING for N ticks, SUCCESS for N ticks, FAILURE for N ticks…

Parameters:
  • name (str) – name of the behaviour
  • n (int) – period value (in ticks)

Note

It does not reset the count when initialising.

update()[source]

Note

User Customisable Callback

Returns:the behaviour’s new status Status
Return type:Status

Subclasses may override this method to perform any logic required to arrive at a decision on the behaviour’s new status. It is the primary worker function called on by the tick() mechanism.

Tip

This method should be almost instantaneous and non-blocking

class py_trees.behaviours.Running(name='Running')

Bases: py_trees.behaviour.Behaviour

class py_trees.behaviours.Success(name='Success')

Bases: py_trees.behaviour.Behaviour

class py_trees.behaviours.SuccessEveryN(name, n)[source]

Bases: py_trees.behaviour.Behaviour

This behaviour updates it’s status with SUCCESS once every N ticks, FAILURE otherwise.

Parameters:
  • name (str) – name of the behaviour
  • n (int) – trigger success on every n’th tick

Tip

Use with decorators to change the status value as desired, e.g. py_trees.decorators.FailureIsRunning()

update()[source]

Note

User Customisable Callback

Returns:the behaviour’s new status Status
Return type:Status

Subclasses may override this method to perform any logic required to arrive at a decision on the behaviour’s new status. It is the primary worker function called on by the tick() mechanism.

Tip

This method should be almost instantaneous and non-blocking

py_trees.blackboard

Blackboards are not a necessary component, but are a fairly standard feature in most behaviour tree implementations. See, for example, the design notes for blackboards in Unreal Engine.

_images/blackboard.jpg

Implementations however, tend to vary quite a bit depending on the needs of the framework using them. Some of the usual considerations include scope and sharing of blackboards across multiple tree instances.

For this package, we’ve decided to keep blackboards extremely simple to fit with the same ‘rapid development for small scale systems’ principles that this library is designed for.

  • No sharing between tree instances
  • No locking for reading/writing
  • Global scope, i.e. any behaviour can access any variable
  • No external communications (e.g. to a database)
class py_trees.blackboard.Blackboard[source]

Bases: object

Borg style key-value store for sharing amongst behaviours.

Examples

You can instantiate the blackboard from anywhere in your program. Even disconnected calls will get access to the same data store. For example:

def check_foo():
    blackboard = Blackboard()
    assert(blackboard.foo, "bar")

if __name__ == '__main__':
    blackboard = Blackboard()
    blackboard.foo = "bar"
    check_foo()

If the key value you are interested in is only known at runtime, then you can set/get from the blackboard without the convenient variable style access:

blackboard = Blackboard()
result = blackboard.set("foo", "bar")
foo = blackboard.get("foo")

The blackboard can also be converted and printed (with highlighting) as a string. This is useful for logging and debugging.

print(Blackboard())

Warning

Be careful of key collisions. This implementation leaves this management up to the user.

See also

The py-trees-demo-blackboard program demos use of the blackboard along with a couple of the blackboard behaviours.

static clear()[source]

Erase the blackboard contents. Typically this is used only when you have repeated runs of different tree instances, as often happens in testing.

get(name)[source]

For when you only have strings to identify and access the blackboard variables, this provides a convenient accessor.

Parameters:name (str) – name of the variable to set
set(name, value, overwrite=True)[source]

For when you only have strings to identify and access the blackboard variables, this provides a convenient setter.

Parameters:
  • name (str) – name of the variable to set
  • value (any) – any variable type
  • overwrite (bool) – whether to abort if the value is already present
Returns:

always True unless overwrite was set to False and a variable already exists

Return type:

bool

unset(name)[source]

For when you need to unset a blackboard variable, this provides a convenient helper method. This is particularly useful for unit testing behaviours.

Parameters:name (str) – name of the variable to unset
class py_trees.blackboard.CheckBlackboardVariable(name, variable_name='dummy', expected_value=None, comparison_operator=<built-in function eq>, clearing_policy=<ClearingPolicy.ON_INITIALISE: 1>, debug_feedback_message=False)[source]

Bases: py_trees.behaviour.Behaviour

Check the blackboard to see if it has a specific variable and optionally whether that variable has an expected value. It is a binary behaviour, always updating it’s status with either SUCCESS or FAILURE at each tick.

initialise()[source]

Clears the internally stored message ready for a new run if old_data_is_valid wasn’t set.

terminate(new_status)[source]

Always discard the matching result if it was invalidated by a parent or higher priority interrupt.

update()[source]

Check for existence, or the appropriate match on the expected value.

Returns:FAILURE if not matched, SUCCESS otherwise.
Return type:Status
class py_trees.blackboard.ClearBlackboardVariable(name='Clear Blackboard Variable', variable_name='dummy')[source]

Bases: py_trees.meta.Success

Clear the specified value from the blackboard.

Parameters:
  • name (str) – name of the behaviour
  • variable_name (str) – name of the variable to clear
initialise()[source]

Delete the variable from the blackboard.

class py_trees.blackboard.SetBlackboardVariable(name='Set Blackboard Variable', variable_name='dummy', variable_value=None)[source]

Bases: py_trees.meta.Success

Set the specified variable on the blackboard. Usually we set variables from inside other behaviours, but can be convenient to set them from a behaviour of their own sometimes so you don’t get blackboard logic mixed up with more atomic behaviours.

Parameters:
  • name (str) – name of the behaviour
  • variable_name (str) – name of the variable to set
  • variable_value (any) – value of the variable to set

Todo

overwrite option, leading to possible failure/success logic.

initialise()[source]

Note

User Customisable Callback

Subclasses may override this method to perform any necessary initialising/clearing/resetting of variables when when preparing to enter this behaviour if it was not previously RUNNING. i.e. Expect this to trigger more than once!

class py_trees.blackboard.WaitForBlackboardVariable(name, variable_name='dummy', expected_value=None, comparison_operator=<built-in function eq>, clearing_policy=<ClearingPolicy.ON_INITIALISE: 1>)[source]

Bases: py_trees.behaviour.Behaviour

Check the blackboard to see if it has a specific variable and optionally whether that variable has a specific value. Unlike CheckBlackboardVariable this class will be in a RUNNING state until the variable appears and (optionally) is matched.

Parameters:
  • name (str) – name of the behaviour
  • variable_name (str) – name of the variable to check
  • expected_value (any) – expected value to find (if None, check for existence only)
  • comparison_operator (func) – one from the python operator module
  • clearing_policy (any) – when to clear the match result, see ClearingPolicy

Tip

There are times when you want to get the expected match once and then save that result thereafter. For example, to flag once a system has reached a subgoal. Use the NEVER flag to do this.

initialise()[source]

Clears the internally stored message ready for a new run if old_data_is_valid wasn’t set.

terminate(new_status)[source]

Always discard the matching result if it was invalidated by a parent or higher priority interrupt.

update()[source]

Check for existence, or the appropriate match on the expected value.

Returns:FAILURE if not matched, SUCCESS otherwise.
Return type:Status

py_trees.common

Common definitions, methods and variables used by the py_trees library.

class py_trees.common.BlackBoxLevel[source]

Bases: enum.IntEnum

Whether a behaviour is a blackbox entity that may be considered collapsible (i.e. everything in its subtree will not be visualised) by visualisation tools.

Blackbox levels are increasingly persistent in visualisations.

Visualisations by default, should always collapse blackboxes that represent DETAIL.

BIG_PICTURE = 3

A blackbox that represents a big picture part of the entire tree view.

COMPONENT = 2

A blackbox that encapsulates a subgroup of functionalities as a single group.

DETAIL = 1

A blackbox that encapsulates detailed activity.

NOT_A_BLACKBOX = 4

Not a blackbox, do not ever collapse.

class py_trees.common.ClearingPolicy[source]

Bases: enum.IntEnum

Policy rules for behaviours to dictate when data should be cleared/reset.

NEVER = 3

Never clear the data

ON_INITIALISE = 1

Clear when entering the initialise() method.

ON_SUCCESS = 2

Clear when returning SUCCESS.

class py_trees.common.Duration[source]

Bases: enum.Enum

Naming conventions.

INFINITE = inf

INFINITE oft used for perpetually blocking operations.

UNTIL_THE_BATTLE_OF_ALFREDO = inf

UNTIL_THE_BATTLE_OF_ALFREDO is an alias for INFINITE.

class py_trees.common.Name[source]

Bases: enum.Enum

Naming conventions.

AUTO_GENERATED = 'AUTO_GENERATED'

AUTO_GENERATED leaves it to the behaviour to generate a useful, informative name.

class py_trees.common.ParallelPolicy[source]

Configurable policies for Parallel behaviours.

class SuccessOnAll(synchronise=True)[source]

Return SUCCESS only when each and every child returns SUCCESS.

class SuccessOnOne[source]

Return SUCCESS so long as at least one child has SUCCESS and the remainder are RUNNING

class SuccessOnSelected(children, synchronise=True)[source]

Retrun SUCCESS so long as each child in a specified list returns SUCCESS.

class py_trees.common.Status[source]

Bases: enum.Enum

An enumerator representing the status of a behaviour

FAILURE = 'FAILURE'

Behaviour check has failed, or execution of its action finished with a failed result.

INVALID = 'INVALID'

Behaviour is uninitialised and inactive, i.e. this is the status before first entry, and after a higher priority switch has occurred.

RUNNING = 'RUNNING'

Behaviour is in the middle of executing some action, result still pending.

SUCCESS = 'SUCCESS'

Behaviour check has passed, or execution of its action has finished with a successful result.

class py_trees.common.VisibilityLevel[source]

Bases: enum.IntEnum

Closely associated with the BlackBoxLevel for a behaviour. This sets the visibility level to be used for visualisations.

Visibility levels correspond to reducing levels of visibility in a visualisation.

ALL = 0

Do not collapse any behaviour.

BIG_PICTURE = 3

Collapse any blackbox that isn’t marked with BIG_PICTURE.

COMPONENT = 2

Collapse blackboxes marked with COMPONENT or lower.

DETAIL = 1

Collapse blackboxes marked with DETAIL or lower.

common.string_to_visibility_level()

Will convert a string to a visibility level. Note that it will quietly return ALL if the string is not matched to any visibility level string identifier.

Parameters:level (str) – visibility level as a string
Returns:visibility level enum
Return type:VisibilityLevel

py_trees.composites

Composites are the factories and decision makers of a behaviour tree. They are responsible for shaping the branches.

digraph selector {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Sequence [fontcolor=black, shape=box, fontsize=11, style=filled, fillcolor=orange];
Selector [fontcolor=black, shape=octagon, fontsize=11, style=filled, fillcolor=cyan];
Chooser [fontcolor=black, shape=doubleoctagon, fontsize=11, style=filled, fillcolor=cyan];
Parallel [fontcolor=black, shape=parallelogram, fontsize=11, style=filled, fillcolor=gold];
}

Tip

You should never need to subclass or create new composites.

Most patterns can be achieved with a combination of the above. Adding to this set exponentially increases the complexity and subsequently making it more difficult to design, introspect, visualise and debug the trees. Always try to find the combination you need to achieve your result before contemplating adding to this set. Actually, scratch that…just don’t contemplate it!

Composite behaviours typically manage children and apply some logic to the way they execute and return a result, but generally don’t do anything themselves. Perform the checks or actions you need to do in the non-composite behaviours.

  • Sequence: execute children sequentially
  • Selector: select a path through the tree, interruptible by higher priorities
  • Chooser: like a selector, but commits to a path once started until it finishes
  • Parallel: manage children concurrently
class py_trees.composites.Chooser(name='Chooser', children=None)[source]

Bases: py_trees.composites.Selector

Choosers are Selectors with Commitment

digraph chooser {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Chooser [fontcolor=black, shape=doubleoctagon, fontsize=11, style=filled, fillcolor=cyan];
"High Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Chooser -> "High Priority";
"Med Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Chooser -> "Med Priority";
"Low Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Chooser -> "Low Priority";
}

A variant of the selector class. Once a child is selected, it cannot be interrupted by higher priority siblings. As soon as the chosen child itself has finished it frees the chooser for an alternative selection. i.e. priorities only come into effect if the chooser wasn’t running in the previous tick.

Note

This is the only composite in py_trees that is not a core composite in most behaviour tree implementations. Nonetheless, this is useful in fields like robotics, where you have to ensure that your manipulator doesn’t drop it’s payload mid-motion as soon as a higher interrupt arrives. Use this composite sparingly and only if you can’t find another way to easily create an elegant tree composition for your task.

Parameters:
  • name (str) – the composite behaviour name
  • children ([Behaviour]) – list of children to add
__init__(name='Chooser', children=None)[source]

Initialize self. See help(type(self)) for accurate signature.

tick()[source]

Run the tick behaviour for this chooser. Note that the status of the tick is (for now) always determined by its children, not by the user customised update function.

Yields:Behaviour – a reference to itself or one of its children
class py_trees.composites.Composite(name: str = <Name.AUTO_GENERATED: 'AUTO_GENERATED'>, children: List[py_trees.behaviour.Behaviour] = None)[source]

Bases: py_trees.behaviour.Behaviour

The parent class to all composite behaviours, i.e. those that have children.

Parameters:
  • name (str) – the composite behaviour name
  • children ([Behaviour]) – list of children to add
__init__(name: str = <Name.AUTO_GENERATED: 'AUTO_GENERATED'>, children: List[py_trees.behaviour.Behaviour] = None)[source]

Initialize self. See help(type(self)) for accurate signature.

add_child(child)[source]

Adds a child.

Parameters:child (Behaviour) – child to add
Raises:TypeError – if the provided child is not an instance of Behaviour
Returns:unique id of the child
Return type:uuid.UUID
add_children(children)[source]

Append a list of children to the current list.

Parameters:children ([Behaviour]) – list of children to add
insert_child(child, index)[source]

Insert child at the specified index. This simply directly calls the python list’s insert method using the child and index arguments.

Parameters:
  • child (Behaviour) – child to insert
  • index (int) – index to insert it at
Returns:

unique id of the child

Return type:

uuid.UUID

prepend_child(child)[source]

Prepend the child before all other children.

Parameters:child (Behaviour) – child to insert
Returns:unique id of the child
Return type:uuid.UUID
remove_all_children()[source]

Remove all children. Makes sure to stop each child if necessary.

remove_child(child)[source]

Remove the child behaviour from this composite.

Parameters:child (Behaviour) – child to delete
Returns:index of the child that was removed
Return type:int

Todo

Error handling for when child is not in this list

remove_child_by_id(child_id)[source]

Remove the child with the specified id.

Parameters:child_id (uuid.UUID) – unique id of the child
Raises:IndexError – if the child was not found
replace_child(child, replacement)[source]

Replace the child behaviour with another.

Parameters:
stop(new_status=<Status.INVALID: 'INVALID'>)[source]

There is generally two use cases that must be supported here.

1) Whenever the composite has gone to a recognised state (i.e. FAILURE or SUCCESS), or 2) when a higher level parent calls on it to truly stop (INVALID).

In only the latter case will children need to be forcibly stopped as well. In the first case, they will have stopped themselves appropriately already.

Parameters:new_status (Status) – behaviour will transition to this new status
tip()[source]

Recursive function to extract the last running node of the tree.

Returns:class::~py_trees.behaviour.Behaviour: the tip function of the current child of this composite or None
class py_trees.composites.Parallel(name: str = <Name.AUTO_GENERATED: 'AUTO_GENERATED'>, policy: py_trees.common.ParallelPolicy.Base = <py_trees.common.ParallelPolicy.SuccessOnAll object>, children: List[py_trees.behaviour.Behaviour] = None)[source]

Bases: py_trees.composites.Composite

Parallels enable a kind of concurrency

digraph pastafarianism {
graph [fontname="times-roman", splines=curved];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Parallel [fillcolor=gold, fontcolor=black, fontsize=9, label="Parallel\n--SuccessOnSelected(⚡,[B1,B2])--", shape=parallelogram, style=filled];
B1 [fillcolor=gray, fontcolor=black, fontsize=9, label=B1, shape=ellipse, style=filled];
Parallel -> B1;
B2 [fillcolor=gray, fontcolor=black, fontsize=9, label=B2, shape=ellipse, style=filled];
Parallel -> B2;
B3 [fillcolor=gray, fontcolor=black, fontsize=9, label=B3, shape=ellipse, style=filled];
Parallel -> B3;
}

Ticks every child every time the parallel is run (a poor man’s form of parallelism).

Parallels with policy SuccessOnSelected will validate themselves just-in-time in the setup() and tick() methods to check if the policy’s selected set of children is a subset of the children of this parallel. Doing this just-in-time is due to the fact that the parallel’s children may change after construction and even dynamically between ticks.

__init__(name: str = <Name.AUTO_GENERATED: 'AUTO_GENERATED'>, policy: py_trees.common.ParallelPolicy.Base = <py_trees.common.ParallelPolicy.SuccessOnAll object>, children: List[py_trees.behaviour.Behaviour] = None)[source]
Parameters:
  • name (str) – the composite behaviour name
  • policy (ParallelPolicy) – policy to use for deciding success or otherwise
  • children ([Behaviour]) – list of children to add
current_child

In some cases it’s clear what the current child is, in others, there is an ambiguity as multiple could exist. If the latter is true, it will return the child relevant farthest down the list.

Returns:the child that is currently running, or None
Return type:Behaviour
setup(**kwargs)[source]

Detect before ticking whether the policy configuration is invalid.

Parameters:

**kwargs (dict) – distribute arguments to this behaviour and in turn, all of it’s children

Raises:
  • RuntimeError – if the parallel’s policy configuration is invalid
  • Exception – be ready to catch if any of the children raise an exception
tick()[source]

Tick over the children.

Yields:Behaviour – a reference to itself or one of its children
Raises:RuntimeError – if the policy configuration was invalid
validate_policy_configuration()[source]

Policy configuration can be invalid if:

  • Policy is SuccessOnSelected and no behaviours have been specified
  • Policy is SuccessOnSelected and behaviours that are not children exist
Raises:RuntimeError – if policy configuration was invalid
verbose_info_string() → str[source]

Provide additional information about the underlying policy.

Returns:name of the policy along with it’s configuration
Return type:str
class py_trees.composites.Selector(name='Selector', children=None)[source]

Bases: py_trees.composites.Composite

Selectors are the Decision Makers

digraph selector {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Selector [fontcolor=black, shape=octagon, fontsize=11, style=filled, fillcolor=cyan];
"High Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Selector -> "High Priority";
"Med Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Selector -> "Med Priority";
"Low Priority" [fontcolor=black, shape=ellipse, fontsize=11, style=filled, fillcolor=gray];
Selector -> "Low Priority";
}

A selector executes each of its child behaviours in turn until one of them succeeds (at which point it itself returns RUNNING or SUCCESS, or it runs out of children at which point it itself returns FAILURE. We usually refer to selecting children as a means of choosing between priorities. Each child and its subtree represent a decreasingly lower priority path.

Note

Switching from a low -> high priority branch causes a stop(INVALID) signal to be sent to the previously executing low priority branch. This signal will percolate down that child’s own subtree. Behaviours should make sure that they catch this and destruct appropriately.

Make sure you do your appropriate cleanup in the terminate() methods! e.g. cancelling a running goal, or restoring a context.

See also

The py-trees-demo-selector program demos higher priority switching under a selector.

Parameters:
  • name (str) – the composite behaviour name
  • children ([Behaviour]) – list of children to add
__init__(name='Selector', children=None)[source]

Initialize self. See help(type(self)) for accurate signature.

__repr__()[source]

Simple string representation of the object.

Returns:string representation
Return type:str
stop(new_status=<Status.INVALID: 'INVALID'>)[source]

Stopping a selector requires setting the current child to none. Note that it is important to implement this here instead of terminate, so users are free to subclass this easily with their own terminate and not have to remember that they need to call this function manually.

Parameters:new_status (Status) – the composite is transitioning to this new status
tick()[source]

Run the tick behaviour for this selector. Note that the status of the tick is always determined by its children, not by the user customised update function.

Yields:Behaviour – a reference to itself or one of its children
class py_trees.composites.Sequence(name='Sequence', children=None)[source]

Bases: py_trees.composites.Composite

Sequences are the factory lines of Behaviour Trees

digraph sequence {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Sequence [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
Guard [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Guard;
"Action 1" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 1";
"Action 2" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 2";
"Action 3" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 3";
}

A sequence will progressively tick over each of its children so long as each child returns SUCCESS. If any child returns FAILURE or RUNNING the sequence will halt and the parent will adopt the result of this child. If it reaches the last child, it returns with that result regardless.

Note

The sequence halts once it sees a child is RUNNING and then returns the result. It does not get stuck in the running behaviour.

See also

The py-trees-demo-sequence program demos a simple sequence in action.

Parameters:
  • name (str) – the composite behaviour name
  • children ([Behaviour]) – list of children to add
__init__(name='Sequence', children=None)[source]

Initialize self. See help(type(self)) for accurate signature.

current_child

Have to check if there’s anything actually running first.

Returns:the child that is currently running, or None
Return type:Behaviour
stop(new_status=<Status.INVALID: 'INVALID'>)[source]

Stopping a sequence requires taking care of the current index. Note that is important to implement this here intead of terminate, so users are free to subclass this easily with their own terminate and not have to remember that they need to call this function manually.

Parameters:new_status (Status) – the composite is transitioning to this new status
tick()[source]

Tick over the children.

Yields:Behaviour – a reference to itself or one of its children

py_trees.console

Simple colour definitions and syntax highlighting for the console.


Colour Definitions

The current list of colour definitions include:

  • Regular: black, red, green, yellow, blue, magenta, cyan, white,
  • Bold: bold, bold_black, bold_red, bold_green, bold_yellow, bold_blue, bold_magenta, bold_cyan, bold_white

These colour definitions can be used in the following way:

import py_trees.console as console
print(console.cyan + "    Name" + console.reset + ": " + console.yellow + "Dude" + console.reset)
py_trees.console.colours = ['', '', '', '', '', '', '', '', '', '', '', '', '', '', '', '', '', '', '', '']

List of all available colours.

py_trees.console.console_has_colours()[source]

Detects if the console (stdout) has colourising capability.

py_trees.console.define_symbol_or_fallback(original: str, fallback: str, encoding: str = 'UTF-8')[source]

Return the correct encoding according to the specified encoding. Used to make sure we get an appropriate symbol, even if the shell is merely ascii as is often the case on, e.g. Jenkins CI.

Parameters:
  • original (str) – the unicode string (usually just a character)
  • fallback (str) – the fallback ascii string
  • encoding (str, optional) – the encoding to check against.
Returns:

either original or fallback depending on whether exceptions were thrown.

Return type:

str

py_trees.console.has_colours = False

Whether the loading program has access to colours or not.

py_trees.console.has_unicode(encoding: str = 'UTF-8') → bool[source]

Define whether the specified encoding has unicode symbols. Usually used to check if the stdout is capable or otherwise (e.g. Jenkins CI can often be configured with unicode disabled).

Parameters:encoding (str, optional) – the encoding to check against.
Returns:true if capable, false otherwise
Return type:bool
py_trees.console.logdebug(message)[source]

Prefixes [DEBUG] and colours the message green.

Parameters:message (str) – message to log.
py_trees.console.logerror(message)[source]

Prefixes [ERROR] and colours the message red.

Parameters:message (str) – message to log.
py_trees.console.logfatal(message)[source]

Prefixes [FATAL] and colours the message bold red.

Parameters:message (str) – message to log.
py_trees.console.loginfo(message)[source]

Prefixes [ INFO] to the message.

Parameters:message (str) – message to log.
py_trees.console.logwarn(message)[source]

Prefixes [ WARN] and colours the message yellow.

Parameters:message (str) – message to log.
py_trees.console.read_single_keypress()[source]

Waits for a single keypress on stdin.

This is a silly function to call if you need to do it a lot because it has to store stdin’s current setup, setup stdin for reading single keystrokes then read the single keystroke then revert stdin back after reading the keystroke.

Returns:the character of the key that was pressed
Return type:int
Raises:KeyboardInterrupt – if CTRL-C was pressed (keycode 0x03)

py_trees.decorators

Decorators are behaviours that manage a single child and provide common modifications to their underlying child behaviour (e.g. inverting the result). That is, they provide a means for behaviours to wear different ‘hats’ and this combinatorially expands the capabilities of your behaviour library.

_images/many-hats.png

An example:

digraph life {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Life [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
Inverter [fillcolor=ghostwhite, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Life -> Inverter;
"Busy?" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Inverter -> "Busy?";
Timeout [fillcolor=ghostwhite, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Life -> Timeout;
"Have a Beer!" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Timeout -> "Have a Beer!";
}
 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
#!/usr/bin/env python

import py_trees.decorators
import py_trees.display

if __name__ == '__main__':

    root = py_trees.composites.Sequence(name="Life")
    timeout = py_trees.decorators.Timeout(
        name="Timeout",
        child=py_trees.behaviours.Success(name="Have a Beer!")
    )
    failure_is_success = py_trees.decorators.Inverter(
        name="Inverter",
        child=py_trees.behaviours.Success(name="Busy?")
        )
    root.add_children([failure_is_success, timeout])
    py_trees.display.render_dot_tree(root)

Decorators (Hats)

Decorators with very specific functionality:

And the X is Y family:

Decorators for Blocking Behaviours

It is worth making a note of the effect of decorators on behaviours that return RUNNING for some time before finally returning SUCCESS or FAILURE (blocking behaviours) since the results are often at first, surprising.

A decorator, such as py_trees.decorators.RunningIsSuccess() on a blocking behaviour will immediately terminate the underlying child and re-intialise on it’s next tick. This is necessary to ensure the underlying child isn’t left in a dangling state (i.e. RUNNING), but is often not what is being sought.

The typical use case being attempted is to convert the blocking behaviour into a non-blocking behaviour. If the underlying child has no state being modified in either the initialise() or terminate() methods (e.g. machinery is entirely launched at init or setup time), then conversion to a non-blocking representative of the original succeeds. Otherwise, another approach is needed. Usually this entails writing a non-blocking counterpart, or combination of behaviours to affect the non-blocking characteristics.

class py_trees.decorators.Condition(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>, status=<Status.SUCCESS: 'SUCCESS'>)[source]

Bases: py_trees.decorators.Decorator

Encapsulates a behaviour and wait for it’s status to flip to the desired state. This behaviour will tick with RUNNING while waiting and SUCCESS when the flip occurs.

__init__(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>, status=<Status.SUCCESS: 'SUCCESS'>)[source]

Initialise with child and optional name, status variables.

Parameters:
  • child (Behaviour) – the child to be decorated
  • name (str) – the decorator name (can be None)
  • status (Status) – the desired status to watch for
update()[source]

SUCCESS if the decorated child has returned the specified status, otherwise RUNNING. This decorator will never return FAILURE

Returns:the behaviour’s new status Status
Return type:Status
class py_trees.decorators.Decorator(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Bases: py_trees.behaviour.Behaviour

A decorator is responsible for handling the lifecycle of a single child beneath

__init__(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Common initialisation steps for a decorator - type checks and name construction (if None is given).

Parameters:
  • name (str) – the decorator name
  • child (Behaviour) – the child to be decorated
Raises:

TypeError – if the child is not an instance of Behaviour

stop(new_status)[source]

As with other composites, it checks if the child is running and stops it if that is the case.

Parameters:new_status (Status) – the behaviour is transitioning to this new status
tick()[source]

A decorator’s tick is exactly the same as a normal proceedings for a Behaviour’s tick except that it also ticks the decorated child node.

Yields:Behaviour – a reference to itself or one of its children
tip()[source]

Get the tip of this behaviour’s subtree (if it has one) after it’s last tick. This corresponds to the the deepest node that was running before the subtree traversal reversed direction and headed back to this node.

Returns:child behaviour, itself or None if its status is INVALID
Return type:Behaviour or None
class py_trees.decorators.FailureIsRunning(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Bases: py_trees.decorators.Decorator

Dont stop running.

update()[source]

Return the decorated child’s status unless it is FAILURE in which case, return RUNNING.

Returns:the behaviour’s new status Status
Return type:Status
class py_trees.decorators.FailureIsSuccess(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Bases: py_trees.decorators.Decorator

Be positive, always succeed.

update()[source]

Return the decorated child’s status unless it is FAILURE in which case, return SUCCESS.

Returns:the behaviour’s new status Status
Return type:Status
class py_trees.decorators.Inverter(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Bases: py_trees.decorators.Decorator

A decorator that inverts the result of a class’s update function.

__init__(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Init with the decorated child.

Parameters:
  • child (Behaviour) – behaviour to time
  • name (str) – the decorator name
update()[source]

Flip FAILURE and SUCCESS

Returns:the behaviour’s new status Status
Return type:Status
class py_trees.decorators.OneShot(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>, policy=<OneShotPolicy.ON_SUCCESSFUL_COMPLETION: [<Status.SUCCESS: 'SUCCESS'>]>)[source]

Bases: py_trees.decorators.Decorator

A decorator that implements the oneshot pattern.

This decorator ensures that the underlying child is ticked through to completion just once and while doing so, will return with the same status as it’s child. Thereafter it will return with the final status of the underlying child.

Completion status is determined by the policy given on construction.

  • With policy ON_SUCCESSFUL_COMPLETION, the oneshot will activate only when the underlying child returns SUCCESS (i.e. it permits retries).
  • With policy ON_COMPLETION, the oneshot will activate when the child returns SUCCESS || FAILURE.
__init__(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>, policy=<OneShotPolicy.ON_SUCCESSFUL_COMPLETION: [<Status.SUCCESS: 'SUCCESS'>]>)[source]

Init with the decorated child.

Parameters:
  • name (str) – the decorator name
  • child (Behaviour) – behaviour to time
  • policy (OneShotPolicy) – policy determining when the oneshot should activate
terminate(new_status)[source]

If returning SUCCESS for the first time, flag it so future ticks will block entry to the child.

tick()[source]

Select between decorator (single child) and behaviour (no children) style ticks depending on whether or not the underlying child has been ticked successfully to completion previously.

update()[source]

Bounce if the child has already successfully completed.

class py_trees.decorators.RunningIsFailure(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Bases: py_trees.decorators.Decorator

Got to be snappy! We want results…yesterday!

update()[source]

Return the decorated child’s status unless it is RUNNING in which case, return FAILURE.

Returns:the behaviour’s new status Status
Return type:Status
class py_trees.decorators.RunningIsSuccess(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Bases: py_trees.decorators.Decorator

Don’t hang around…

update()[source]

Return the decorated child’s status unless it is RUNNING in which case, return SUCCESS.

Returns:the behaviour’s new status Status
Return type:Status
class py_trees.decorators.SuccessIsFailure(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Bases: py_trees.decorators.Decorator

Be depressed, always fail.

update()[source]

Return the decorated child’s status unless it is SUCCESS in which case, return FAILURE.

Returns:the behaviour’s new status Status
Return type:Status
class py_trees.decorators.SuccessIsRunning(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>)[source]

Bases: py_trees.decorators.Decorator

It never ends…

update()[source]

Return the decorated child’s status unless it is SUCCESS in which case, return RUNNING.

Returns:the behaviour’s new status Status
Return type:Status
class py_trees.decorators.Timeout(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>, duration=5.0)[source]

Bases: py_trees.decorators.Decorator

A decorator that applies a timeout pattern to an existing behaviour. If the timeout is reached, the encapsulated behaviour’s stop() method is called with status FAILURE otherwise it will simply directly tick and return with the same status as that of it’s encapsulated behaviour.

__init__(child, name=<Name.AUTO_GENERATED: 'AUTO_GENERATED'>, duration=5.0)[source]

Init with the decorated child and a timeout duration.

Parameters:
  • child (Behaviour) – behaviour to time
  • name (str) – the decorator name
  • duration (float) – timeout length in seconds
initialise()[source]

Reset the feedback message and finish time on behaviour entry.

update()[source]

Terminate the child and return FAILURE if the timeout is exceeded.

py_trees.display

Behaviour trees are significantly easier to design, monitor and debug with visualisations. Py Trees does provide minimal assistance to render trees to various simple output formats. Currently this includes dot graphs, strings or stdout.

Warning

There is both disrespect for ascii and lack of recognition for unicode in this file as the intention to make ascii art a first class citizen in py_trees became tainted by the desire to make use of the very fine looking unicode symbols underneath. If such behaviour offends, please wear your peril-sensitive sunglasses when parsing or using this module.

py_trees.display.ascii_tree(root, show_status=False, visited={}, previously_visited={}, indent=0)[source]

Graffiti your console with with ascii trees.

Parameters:
  • root (Behaviour) – the root of the tree, or subtree you want to show
  • indent (int) – the number of characters to indent the tree
  • show_status (bool) – always show status and feedback message (i.e. for every element, not just those visited)
  • visited (dict) – dictionary of (uuid.UUID) and status (Status) pairs for behaviours visited on the current tick
  • previously_visited (dict) – dictionary of behaviour id/status pairs from the previous tree tick
Returns:

an ascii tree (i.e. in string form)

Return type:

str

Examples

Use the SnapshotVisitor and BehaviourTree to generate snapshot information at each tick and feed that to a post tick handler that will print the traversed ascii tree complete with status and feedback messages.

_images/ascii_tree.png
def post_tick_handler(snapshot_visitor, behaviour_tree):
    print(
        py_trees.display.ascii_tree(
            behaviour_tree.root,
            visited=snapshot_visitor.visited,
            previously_visited=snapshot_visitor.visited
        )
    )

root = py_trees.composites.Sequence("Sequence")
for action in ["Action 1", "Action 2", "Action 3"]:
    b = py_trees.behaviours.Count(
            name=action,
            fail_until=0,
            running_until=1,
            success_until=10)
    root.add_child(b)
behaviour_tree = py_trees.trees.BehaviourTree(root)
snapshot_visitor = py_trees.visitors.SnapshotVisitor()
behaviour_tree.add_post_tick_handler(
    functools.partial(post_tick_handler,
                      snapshot_visitor))
behaviour_tree.visitors.append(snapshot_visitor)
py_trees.display.dot_graph(root: py_trees.behaviour.Behaviour, visibility_level: py_trees.common.VisibilityLevel = <VisibilityLevel.DETAIL: 1>, collapse_decorators: bool = False, with_qualified_names: bool = False)[source]

Generate the pydot graph - this is usually the first step in rendering the tree to file. See also render_dot_tree().

Parameters:
  • root (Behaviour) – the root of a tree, or subtree
  • ( (visibility_level) – class`~py_trees.common.VisibilityLevel`): collapse subtrees at or under this level
  • collapse_decorators (bool, optional) – only show the decorator (not the child), defaults to False
  • with_qualified_names – (bool, optional): print the class information for each behaviour in each node, defaults to False
Returns:

graph

Return type:

pydot.Dot

Examples

# convert the pydot graph to a string object
print("{}".format(py_trees.display.dot_graph(root).to_string()))
py_trees.display.render_dot_tree(root: py_trees.behaviour.Behaviour, visibility_level: py_trees.common.VisibilityLevel = <VisibilityLevel.DETAIL: 1>, collapse_decorators: bool = False, name: str = None, target_directory: str = '/home/docs/checkouts/readthedocs.org/user_builds/py-trees/checkouts/release-1.1.x/doc', with_qualified_names: bool = False)[source]

Render the dot tree to .dot, .svg, .png. files in the current working directory. These will be named with the root behaviour name.

Parameters:
  • root (Behaviour) – the root of a tree, or subtree
  • ( (visibility_level) – class`~py_trees.common.VisibilityLevel`): collapse subtrees at or under this level
  • collapse_decorators (bool) – only show the decorator (not the child)
  • name (str) – name to use for the created files (defaults to the root behaviour name)
  • target_directory (str) – default is to use the current working directory, set this to redirect elsewhere
  • with_qualified_names (bool) – print the class names of each behaviour in the dot node

Example

Render a simple tree to dot/svg/png file:

digraph sequence {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
Sequence [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
Guard [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Guard;
"Action 1" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 1";
"Action 2" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 2";
"Action 3" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 3";
}
root = py_trees.composites.Sequence("Sequence")
for job in ["Action 1", "Action 2", "Action 3"]:
    success_after_two = py_trees.behaviours.Count(name=job,
                                                  fail_until=0,
                                                  running_until=1,
                                                  success_until=10)
    root.add_child(success_after_two)
py_trees.display.render_dot_tree(root)

Tip

A good practice is to provide a command line argument for optional rendering of a program so users can quickly visualise what tree the program will execute.

py_trees.idioms

A library of subtree creators that build complex patterns of behaviours representing common behaviour tree idioms.

py_trees.idioms.oneshot(name='OneShot Idiom', variable_name='oneshot', behaviour=<py_trees.meta.Dummy object>, policy=<OneShotPolicy.ON_SUCCESSFUL_COMPLETION: [<Status.SUCCESS: 'SUCCESS'>]>)[source]

Ensure that a particular pattern is executed through to completion just once. Thereafter it will just rebound with success.

digraph oneshot {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
OneShot [fillcolor=cyan, fontcolor=black, fontsize=11, shape=octagon, style=filled];
"Oneshot w/ Guard" [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
OneShot -> "Oneshot w/ Guard";
"Not Completed?" [fillcolor=ghostwhite, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Oneshot w/ Guard" -> "Not Completed?";
"Completed?" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
"Not Completed?" -> "Completed?";
Sequence [fillcolor=orange, fontcolor=black, fontsize=11, shape=box, style=filled];
"Oneshot w/ Guard" -> Sequence;
Guard [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> Guard;
"Action 1" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 1";
"Action 2" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 2";
"Action 3" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Action 3";
"Mark Done\n[SUCCESS]" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
Sequence -> "Mark Done\n[SUCCESS]";
"Oneshot Result" [fillcolor=gray, fontcolor=black, fontsize=11, shape=ellipse, style=filled];
OneShot -> "Oneshot Result";
}

Note

Completion on FAILURE or on SUCCESS only (permits retries if it fails) is determined by the policy.

Parameters:
  • name (str) – the name to use for the oneshot root (selector)
  • variable_name (str) – name for the flag used on the blackboard (ensure it is unique)
  • behaviour (Behaviour) – single behaviour or composited subtree to oneshot
  • policy (OneShotPolicy) – policy determining when the oneshot should activate
Returns:

the root of the oneshot subtree

Return type:

Behaviour

py_trees.idioms.pick_up_where_you_left_off(name='Pickup Where You Left Off Idiom', tasks=[<py_trees.meta.Dummy object>, <py_trees.meta.Dummy object>])[source]

Rudely interrupted while enjoying a sandwich, a caveman (just because they wore loincloths does not mean they were not civilised), picks up his club and fends off the sabre-tooth tiger invading his sanctum as if he were swatting away a gnat. Task accomplished, he returns to the joys of munching through the layers of his sandwich.

digraph pick_up_where_you_left_off {
graph [fontname="times-roman"];
node [fontname="times-roman"];
edge [fontname="times-roman"];
"Pick Up Where You Left Off" [shape=octagon, style=filled, fillcolor=cyan, fontsize=11, fontcolor=black];
"High Priority" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Pick Up Where You Left Off" -> "High Priority";
Tasks [shape=box, style=filled, fillcolor=orange, fontsize=11, fontcolor=black];
"Pick Up Where You Left Off" -> Tasks;
"Do or Don't" [shape=octagon, style=filled, fillcolor=cyan, fontsize=11, fontcolor=black];
Tasks -> "Do or Don't";
"Done?" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Do or Don't" -> "Done?";
Worker [shape=box, style=filled, fillcolor=orange, fontsize=11, fontcolor=black];
"Do or Don't" -> Worker;
"Task 1" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Worker -> "Task 1";
"Mark\ntask_1_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Worker -> "Mark\ntask_1_done";
"Do or Don't*" [shape=octagon, style=filled, fillcolor=cyan, fontsize=11, fontcolor=black];
Tasks -> "Do or Don't*";
"Done?*" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Do or Don't*" -> "Done?*";
"Worker*" [shape=box, style=filled, fillcolor=orange, fontsize=11, fontcolor=black];
"Do or Don't*" -> "Worker*";
"Task 2" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Worker*" -> "Task 2";
"Mark\ntask_2_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
"Worker*" -> "Mark\ntask_2_done";
"Clear\ntask_1_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Tasks -> "Clear\ntask_1_done";
"Clear\ntask_2_done" [shape=ellipse, style=filled, fillcolor=gray, fontsize=11, fontcolor=black];
Tasks -> "Clear\ntask_2_done";
}

Note

There are alternative ways to accomplish this idiom with their pros and cons.

a) The tasks in the sequence could be replaced by a factory behaviour that dynamically checks the state of play and spins up the tasks required each time the task sequence is first entered and invalidates/deletes them when it is either finished or invalidated. That has the advantage of not requiring much of the blackboard machinery here, but disadvantage in not making visible the task sequence itself at all times (i.e. burying details under the hood).

b) A new composite which retains the index between initialisations can also achieve the same pattern with fewer blackboard shenanigans, but suffers from an increased logical complexity cost for your trees (each new composite increases decision making complexity (O(n!)).

Parameters:
  • name (str) – the name to use for the task sequence behaviour
  • tasks ([Behaviour) – lists of tasks to be sequentially performed
Returns:

root of the generated subtree

Return type:

Behaviour

py_trees.meta

Meta methods to create behaviours without needing to create the behaviours themselves.

py_trees.meta.create_behaviour_from_function(func)[source]

Create a behaviour from the specified function, dropping it in for the Behaviour update() method. Ths function must include the self argument and return a Status value. It also automatically provides a drop-in for the terminate() method that clears the feedback message. Other methods are left untouched.

Parameters:func (function) – a drop-in for the update() method

py_trees.timers

Time related behaviours.

class py_trees.timers.Timer(name='Timer', duration=5.0)[source]

Bases: py_trees.behaviour.Behaviour

Simple timer class that is RUNNING until the timer runs out, at which point it is SUCCESS. This can be used in a wide variety of situations - pause, duration, timeout depending on how it is wired into the tree (e.g. pause in a sequence, duration/timeout in a parallel).

The timer gets reset either upon entry (initialise()) if it hasn’t already been set and gets cleared when it either runs out, or the behaviour is interrupted by a higher priority or parent cancelling it.

Parameters:
  • name (str) – name of the behaviour
  • duration (int) – length of time to run (in seconds)
Raises:

TypeError – if the provided duration is not a real number

Note

This succeeds the first time the behaviour is ticked after the expected finishing time.

Tip

Use the RunningIsFailure() decorator if you need FAILURE until the timer finishes.

__init__(name='Timer', duration=5.0)[source]

Initialize self. See help(type(self)) for accurate signature.

initialise()[source]

Store the expected finishing time.

terminate(new_status)[source]

Clear the expected finishing time.

update()[source]

Check current time against the expected finishing time. If it is in excess, flip to SUCCESS.

py_trees.trees

class py_trees.trees.BehaviourTree(root: py_trees.behaviour.Behaviour)[source]

Bases: object

Grow, water, prune your behaviour tree with this, the default reference implementation. It features a few enhancements to provide richer logging, introspection and dynamic management of the tree itself:

  • Pre and post tick handlers to execute code automatically before and after a tick
  • Visitor access to the parts of the tree that were traversed in a tick
  • Subtree pruning and insertion operations
  • Continuous tick-tock support

See also

The py-trees-demo-tree-stewardship program demonstrates the above features.

Parameters:

root (Behaviour) – root node of the tree

Variables:
  • count (int) – number of times the tree has been ticked.
  • root (Behaviour) – root node of the tree
  • visitors ([visitors]) – entities that visit traversed parts of the tree when it ticks
  • pre_tick_handlers ([func]) – functions that run before the entire tree is ticked
  • post_tick_handlers ([func]) – functions that run after the entire tree is ticked
Raises:

TypeError – if root variable is not an instance of Behaviour

add_post_tick_handler(handler)[source]

Add a function to execute after the tree has ticked. The function must have a single argument of type BehaviourTree.

Some ideas that are often used:

  • logging
  • modifications on the tree itself (e.g. closing down a plan)
  • sending data to visualisation tools
  • introspect the state of the tree to make and send reports
Parameters:handler (func) – function
add_pre_tick_handler(handler)[source]

Add a function to execute before the tree is ticked. The function must have a single argument of type BehaviourTree.

Some ideas that are often used:

  • logging (to file or stdout)
  • modifications on the tree itself (e.g. starting a new plan)
Parameters:handler (func) – function
add_visitor(visitor)[source]

Trees can run multiple visitors on each behaviour as they tick through a tree.

Parameters:visitor (VisitorBase) – sub-classed instance of a visitor
destroy()[source]

Destroy the tree by stopping the root node.

insert_subtree(child, unique_id, index)[source]

Insert a subtree as a child of the specified parent. If the parent is found, this directly calls the parent’s insert_child() method using the child and index arguments.

Parameters:
  • child (Behaviour) – subtree to insert
  • unique_id (uuid.UUID) – unique id of the parent
  • index (int) – insert the child at this index, pushing all children after it back one.
Returns:

suceess or failure (parent not found) of the operation

Return type:

bool

Raises:

TypeError – if the parent is not a Composite

Todo

Could use better, more informative error handling here. Especially if the insertion has its own error handling (e.g. index out of range). Could also use a different api that relies on the id of the sibling node it should be inserted before/after.

interrupt()[source]

Interrupt tick-tock if it is tick-tocking. Note that this will permit a currently executing tick to finish before interrupting the tick-tock.

prune_subtree(unique_id)[source]

Prune a subtree given the unique id of the root of the subtree.

Parameters:unique_id (uuid.UUID) – unique id of the subtree root
Returns:success or failure of the operation
Return type:bool
Raises:RuntimeError – if unique id is the behaviour tree’s root node id
replace_subtree(unique_id, subtree)[source]

Replace the subtree with the specified id for the new subtree. This is a common pattern where we’d like to swap out a whole sub-behaviour for another one.

Parameters:
  • unique_id (uuid.UUID) – unique id of the parent
  • subtree (Behaviour) – root behaviour of the subtree
Raises
AssertionError: if unique id is the behaviour tree’s root node id
Returns:suceess or failure of the operation
Return type:bool
setup(timeout: float = <Duration.INFINITE: inf>, visitor: py_trees.visitors.VisitorBase = None, **kwargs)[source]

Crawls across the tree calling setup() on each behaviour.

Visitors can optionally be provided to provide a node-by-node analysis on the result of each node’s setup() before the next node’s setup() is called. This is useful on trees with relatively long setup times to progressively report out on the current status of the operation.

Parameters:
  • timeout (float) – time (s) to wait (use common.Duration.INFINITE to block indefinitely)
  • visitor (VisitorBase) – runnable entities on each node after it’s setup
  • **kwargs (dict) – distribute arguments to this behaviour and in turn, all of it’s children
Raises:
  • Exception – be ready to catch if any of the behaviours raise an exception
  • RuntimeError – in case setup() times out
tick(pre_tick_handler=None, post_tick_handler=None)[source]

Tick the tree just once and run any handlers before and after the tick. This optionally accepts some one-shot handlers (c.f. those added by add_pre_tick_handler() and add_post_tick_handler() which will be automatically run every time).

The handler functions must have a single argument of type BehaviourTree.

Parameters:
  • pre_tick_handler (func) – function to execute before ticking
  • post_tick_handler (func) – function to execute after ticking
tick_tock(period_ms, number_of_iterations=-1, pre_tick_handler=None, post_tick_handler=None)[source]

Tick continuously with period as specified. Depending on the implementation, the period may be more or less accurate and may drift in some cases (the default implementation here merely assumes zero time in tick and sleeps for this duration of time and consequently, will drift).

This optionally accepts some handlers that will be used for the duration of this tick tock (c.f. those added by add_pre_tick_handler() and add_post_tick_handler() which will be automatically run every time).

The handler functions must have a single argument of type BehaviourTree.

Parameters:
  • period_ms (float) – sleep this much between ticks (milliseconds)
  • number_of_iterations (int) – number of iterations to tick-tock
  • pre_tick_handler (func) – function to execute before ticking
  • post_tick_handler (func) – function to execute after ticking
tip()[source]

Get the tip of the tree. This corresponds to the the deepest node that was running before the subtree traversal reversed direction and headed back to this node.

Returns:child behaviour, itself or None if its status is INVALID
Return type:Behaviour or None

See also

tip()

py_trees.trees.setup_tree_ascii_art_debug(tree: py_trees.trees.BehaviourTree)[source]

Convenience method for configuring a tree to paint an ascii art snapshot on your console at the end of every tick.

Parameters:tree (BehaviourTree) – the behaviour tree that has just been ticked

py_trees.utilities

Assorted utility functions.

class py_trees.utilities.Process(*args, **kwargs)[source]

Bases: multiprocessing.context.Process

run()[source]

Method to be run in sub-process; can be overridden in sub-class

py_trees.utilities.get_fully_qualified_name(instance: object) → str[source]

Get at the fully qualified name of an object, e.g. an instance of a Sequence becomes ‘py_trees.composites.Sequence’.

Parameters:instance (object) – an instance of any class
Returns:the fully qualified name
Return type:str
py_trees.utilities.get_valid_filename(s: str) → str[source]

Return the given string converted to a string that can be used for a clean filename (without extension). Remove leading and trailing spaces; convert other spaces and newlines to underscores; and remove anything that is not an alphanumeric, dash, underscore, or dot.

>>> utilities.get_valid_filename("john's portrait in 2004.jpg")
'johns_portrait_in_2004.jpg'
Parameters:program (str) – string to convert to a valid filename
Returns:a representation of the specified string as a valid filename
Return type:str
py_trees.utilities.static_variables(**kwargs)[source]

This is a decorator that can be used with python methods to attach initialised static variables to the method.

@static_variables(counter=0)
def foo():
    foo.counter += 1
    print("Counter: {}".format(foo.counter))
py_trees.utilities.which(program)[source]

Wrapper around the command line ‘which’ program.

Parameters:program (str) – name of the program to find.
Returns:path to the program or None if it doesnt exist.
Return type:str

py_trees.visitors

Visitors are entities that can be passed to a tree implementation (e.g. BehaviourTree) and used to either visit each and every behaviour in the tree, or visit behaviours as the tree is traversed in an executing tick. At each behaviour, the visitor runs its own method on the behaviour to do as it wishes - logging, introspecting, etc.

Warning

Visitors should not modify the behaviours they visit.

class py_trees.visitors.DebugVisitor[source]

Bases: py_trees.visitors.VisitorBase

Picks up and logs feedback messages and the behaviour’s status. Logging is done with the behaviour’s logger.

run(behaviour)[source]

This method gets run as each behaviour is ticked. Override it to perform some activity - e.g. introspect the behaviour to store/process logging data for visualisations.

Parameters:behaviour (Behaviour) – behaviour that is ticking
class py_trees.visitors.SnapshotVisitor(full=False)[source]

Bases: py_trees.visitors.VisitorBase

Visits the tree in tick-tock, recording the id/status of the visited set of nodes. Additionally caches the last tick’s visited collection for comparison.

Parameters:

full (bool) – flag to indicate whether it should be used to visit only traversed nodes or the entire tree

Variables:
  • visited (dict) – dictionary of behaviour id (uuid.UUID) and status (Status) pairs
  • previously_visited (dict) – dictionary of behaviour id’s saved from the previous tree tick

See also

This visitor is used with the BehaviourTree class to collect information and generate_ascii_tree() to display information.

initialise()[source]

Cache the last collection of visited nodes and reset the dictionary.

run(behaviour)[source]

This method gets run as each behaviour is ticked. Catch the id and status and store it.

Parameters:behaviour (Behaviour) – behaviour that is ticking
class py_trees.visitors.VisitorBase(full=False)[source]

Bases: object

Parent template for visitor types.

Visitors are primarily designed to work with BehaviourTree but they can be used in the same way for other tree custodian implementations.

Parameters:full (bool) – flag to indicate whether it should be used to visit only traversed nodes or the entire tree
Variables:full (bool) – flag to indicate whether it should be used to visit only traversed nodes or the entire tree
initialise()[source]

Override this method if any resetting of variables needs to be performed between ticks (i.e. visitations).

run(behaviour)[source]

This method gets run as each behaviour is ticked. Override it to perform some activity - e.g. introspect the behaviour to store/process logging data for visualisations.

Parameters:behaviour (Behaviour) – behaviour that is ticking
class py_trees.visitors.WindsOfChangeVisitor[source]

Bases: py_trees.visitors.VisitorBase

Visits the ticked part of a tree, checking off the status against the set of status results recorded in the previous tick. If there has been a change, it flags it. This is useful for determining when to trigger, e.g. logging.

Variables:
  • changed (Bool) – flagged if there is a difference in the visited path or Status of any behaviour on the path
  • ticked_nodes (dict) – dictionary of behaviour id (uuid.UUID) and status (Status) pairs from the current tick
  • previously_ticked+nodes (dict) – dictionary of behaviour id (uuid.UUID) and status (Status) pairs from the previous tick
  • running_nodes ([uuid.UUID]) – list of id’s for behaviours which were traversed in the current tick
  • previously_running_nodes ([uuid.UUID]) – list of id’s for behaviours which were traversed in the last tick

See also

The py-trees-demo-logging program demonstrates use of this visitor to trigger logging of a tree serialisation.

initialise()[source]

Switch running to previously running and then reset all other variables. This should get called before a tree ticks.

run(behaviour)[source]

This method gets run as each behaviour is ticked. Catch the id and status and store it. Additionally add it to the running list if it is RUNNING.

Parameters:behaviour (Behaviour) – behaviour that is ticking

Release Notes

1.1.0 (2019-03-19)

Breaking API

  • [display] print_ascii_tree -> ascii_tree, #178.
  • [display] generate_pydot_graph -> dot_graph, #178.
  • [trees] tick_tock(sleep_ms, ..) -> tick_tock(period_ms, …), #182.

New Features

  • [trees] add missing add_visitor method
  • [trees] flexible setup() for children via kwargs
  • [trees] convenience method for ascii tree debugging
  • [display] highlight the tip in ascii tree snapshots

Bugfixes

  • [trees] threaded timers for setup (avoids multiprocessing problems)
  • [behaviour|composites] bugfix tip behaviour, add tests
  • [display] correct first indent when non-zero in ascii_tree
  • [display] apply same formatting to root as children in ascii_tree

1.0.7 (2019-xx-yy)

  • [display] optional arguments for generate_pydot_graph

1.0.6 (2019-03-06)

  • [decorators] fix missing root feedback message in ascii graphs

1.0.5 (2019-02-28)

  • [decorators] fix timeout bug that doesn’t respect a child’s last tick

1.0.4 (2019-02-26)

  • [display] drop spline curves, it’s buggy with graphviz 2.38

1.0.3 (2019-02-13)

  • [visitors] winds of change visitor and logging demo

1.0.2 (2019-02-13)

  • [console] fallbacks for unicode chars when (UTF-8) encoding cannot support them

1.0.1 (2018-02-12)

  • [trees] don’t use multiprocess on setup if not using timeouts

1.0.0 (2019-01-18)

Breaking API

  • [behaviour] setup() no longer returns a boolean, catch exceptions instead, #143.
  • [behaviour] setup() no longer takes timeouts, responsibility moved to BehaviourTree, #148.
  • [decorators] new-style decorators found in py_trees.decorators
  • [decorators] new-style decorators stop their running child on completion (SUCCESS||FAILURE)
  • [decorators] old-style decorators in py_trees.meta deprecated

New Features

  • [blackboard] added a method for clearing the entire blackboard (useful for tests)
  • [composites] raise TypeError when children’s setup methods don’t return a bool (common mistake)
  • [composites] new parallel policies, SuccessOnAll, SuccessOnSelected
  • [decorators] oneshot policies for activating on completion or successful completion only
  • [meta] behaviours from functions can now automagically generate names

0.8.x (2018-10-18)

Breaking API

  • Lower level namespace types no longer exist (PR117), e.g. py_trees.Status -> py_trees.common.Status
  • Python2 support dropped

New Features

  • [idioms] ‘Pick Up Where You Left Off’
  • [idioms] ‘OneShot’

0.8.0 (2018-10-18)

  • [infra] shortcuts to types in __init__.py removed (PR117)
  • [bugfix] python3 rosdeps
  • [idioms] pick_up_where_you_left_off added

0.7.5 (2018-10-10)

  • [idioms] oneshot added
  • [bugfix] properly set/reset parents when replacing/removing children in composites

0.7.0 (2018-09-27)

  • [announce] python3 only support from this point forward
  • [announce] now compatible for ros2 projects

0.6.5 (2018-09-19)

  • [bugfix] pick up missing feedback messages in inverters
  • [bugfix] eliminate costly/spammy blackboard variable check feedback message

0.6.4 (2018-09-19)

  • [bugfix] replace awkward newlines with spaces in ascii trees

0.6.3 (2018-09-04)

  • [bugfix] don’t send the parellel’s status to running children, invalidate them instead

0.6.2 (2018-08-31)

  • [bugfix] oneshot now reacts to priority interrupts correctly

0.6.1 (2018-08-20)

  • [bugfix] oneshot no longer permanently modifies the original class

0.6.0 (2018-05-15)

  • [infra] python 2/3 compatibility

0.5.10 (2017-06-17)

  • [meta] add children monkeypatching for composite imposters
  • [blackboard] check for nested variables in WaitForBlackboard

0.5.9 (2017-03-25)

  • [docs] bugfix image links and rewrite the motivation

0.5.8 (2017-03-19)

  • [infra] setup.py tests_require, not test_require

0.5.7 (2017-03-01)

  • [infra] update maintainer email

0.5.5 (2017-03-01)

  • [docs] many minor doc updates
  • [meta] bugfix so that imposter now ticks over composite children
  • [trees] method for getting the tip of the tree
  • [programs] py-trees-render program added

0.5.4 (2017-02-22)

  • [infra] handle pypi/catkin conflicts with install_requires

0.5.2 (2017-02-22)

  • [docs] disable colour when building
  • [docs] sidebar headings
  • [docs] dont require project installation

0.5.1 (2017-02-21)

  • [infra] pypi package enabled

0.5.0 (2017-02-21)

  • [ros] components moved to py_trees_ros
  • [timeout] bugfix to ensure timeout decorator initialises properly
  • [docs] rolled over with napolean style
  • [docs] sphinx documentation updated
  • [imposter] make sure tip() drills down into composites
  • [demos] re-organised into modules

0.4.0 (2017-01-13)

  • [trees] add pre/post handlers after setup, just in case setup fails
  • [introspection] do parent lookups so you can crawl back up a tree
  • [blackboard] permit init of subscriber2blackboard behaviours
  • [blackboard] watchers
  • [timers] better feedback messages
  • [imposter] ensure stop() directly calls the composited behaviour

0.3.0 (2016-08-25)

  • failure_is_running decorator (meta).

0.2.0 (2016-06-01)

  • do terminate properly amongst relevant classes
  • blackboxes
  • chooser variant of selectors
  • bugfix the decorators
  • blackboard updates on change only
  • improved dot graph creation
  • many bugfixes to composites
  • subscriber behaviours
  • timer behaviours

0.1.2 (2015-11-16)

  • one shot sequences
  • abort() renamed more appropriately to stop()

0.1.1 (2015-10-10)

  • lots of bugfixing stabilising py_trees for the spain field test
  • complement decorator for behaviours
  • dot tree views
  • ascii tree and tick views
  • use generators and visitors to more efficiently walk/introspect trees
  • a first implementation of behaviour trees in python

Indices and tables