Module API

py_trees_ros

ROS extensions, behaviours and utilities for py_trees.

py_trees_ros.actions

Various instantiable templates for action client/server style behaviours.

class py_trees_ros.actions.ActionClient(name='Action Client', action_spec=None, action_goal=None, action_namespace='/action', override_feedback_message_on_running='moving')[source]

Bases: py_trees.behaviour.Behaviour

A generic action client interface. This simply sends a pre-configured goal to the action client.

Cases where you might want to subclass and extend this behaviour:

  • Update the goal data in initialise()
    • e.g. use blackboard data to determine the new characteristics of your goal
  • Trigger true pre-emption by sending a new goal in update()
Parameters:
  • name (str) – name of the behaviour
  • action_spec (any) – spec type for the action (e.g. move_base_msgs.msg.MoveBaseAction)
  • action_goal (any) – preconfigured action goal (e.g. move_base_msgs.msg.MoveBaseGoal())
  • action_namespace (str) – where you can find the action topics
  • override_feedback_message_on_running (str) – override the feedback message from the server

Feedback messages are often accompanied with detailed messages that continuously change - since these are not significant and we don’t want to log every change due to these messages, you can provide an override here that simply signifies the action is running.

@todo: a more comprehensive way of filtering/parsing feedback messages to customise a running state so that it can identify and react to ‘significant’ events while running.

initialise()[source]

Reset the internal variables.

setup(timeout)[source]
Parameters:timeout (float) – time to wait (0.0 is blocking forever)
Returns:whether it timed out trying to setup
Return type:bool
terminate(new_status)[source]

If running and the current goal has not already succeeded, cancel it.

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

Check only to see whether the underlying action server has succeeded, is running, or has cancelled/aborted for some reason and map these to the usual behaviour return states.

py_trees_ros.battery

Getting the most out of your battery.

class py_trees_ros.battery.ToBlackboard(name, topic_name='/battery/state', threshold=30.0)[source]

Bases: py_trees_ros.subscribers.ToBlackboard

Subscribes to the battery message and writes battery data to the blackboard. Also adds a warning flag to the blackboard if the battery is low - note that it does some buffering against ping-pong problems so the warning doesn’t trigger on/off rapidly when close to the threshold.

When ticking, updates with RUNNING if it got no data, SUCCESS otherwise.

Blackboard Variables:
  • battery (sensor_msgs.msg.BatteryState)[w]: the raw battery message
  • battery_low_warning (bool)[w]: False if battery is ok, True if critically low
Parameters:
  • name (str) – name of the behaviour
  • topic_name (str) – name of the battery state topic
  • threshold (float) – percentage level threshold for flagging as low (0-100)
update()[source]

Call the parent to write the raw data to the blackboard and then check against the threshold to determine if the low warning flag should also be updated.

py_trees_ros.blackboard

The Blackboard Exchange wraps a Blackboard with a ROS API to provide easy introspection of a blackboard from outside the tree. This includes both lazily publishing of the entire board when there’s a change as well as services to open windows onto parts of the blackboard for when the entirity becomes too noisy to track.

You get this for free in the ROS Behaviour Tree manager and the py-trees-blackboard-watcher command line utility provides a convenient means of interacting with the watching services.

class py_trees_ros.blackboard.Exchange[source]

Bases: object

Establishes ros communications around a Blackboard that enable users to introspect or watch relevant parts of the blackboard.

ROS Publishers:
  • ~blackboard (std_msgs.msg.String)
    • streams (string form) the contents of the entire blackboard as it updates
ROS Services:
  • ~get_blackboard_variables (py_trees_msgs.srv.GetBlackboardVariables)
    • list all the blackboard variable names (not values)
  • ~open_blackboard_watcher (py_trees_msgs.srv.OpenBlackboardWatcher)
    • request a publisher to stream a part of the blackboard contents
  • ~close_blackboard_watcher (py_trees_msgs.srv.CloseBlackboardWatcher)
    • close a previously opened watcher

Watching could be more simply enabled by just providing a get stye service on a particular variable(s), however that would introduce an asynchronous interrupt on the library’s usage and subsequently, locking. Instead, a watcher service requests for a stream, i.e. a publisher to be created for private use that streams only a subsection of the blackboard to the user. Additional services are provided for closing the stream and listing the variables on the blackboard.

See also

BehaviourTree (in which it is used) and py-trees-blackboard-watcher (working with the watchers).

blackboard = None

Internal handle to the blackboard. Users can utilise this, or create their own handles via the usual, e.g.

my_blackboard = py_trees.blackboard.Blackboard()
publish_blackboard(unused_tree=None)[source]

Lazy string publishing of the blackboard (the contents of the blackboard can be of many and varied types, so string form is the only way to transmit this across a ros message) on the ~blackboard topic.

Typically you would call this from a tree custodian (e.g. py_trees_ros.trees.BehaviourTree) after each and every tick.

Note

Lazy: it will only do the relevant string processing if there are subscribers present.

Parameters:unused_tree (any) – if used as a post_tick_handler, needs the argument, but nonetheless, gets unused
setup(timeout)[source]

This is where the ros initialisation of publishers and services happens. It is kept outside of the constructor for the same reasons that the familiar py_trees setup() method has - to enable construction of behaviours and trees offline (away from their execution environment) so that dot graphs and other visualisations of the tree can be created.

Parameters:timeout (float) – time to wait (0.0 is blocking forever)
Returns:suceess or failure of the operation
Return type:bool

Examples

It is expected that users will use this in their own customised tree custodian:

class MyTreeManager(py_trees.trees.BehaviourTree):

    def __init__(self):
        pass

    def setup(self, timeout):
        super(MyTreeManager, self).setup(timeout)
        self.exchange = py_trees_ros.blackboard.Exchange()
        self.exchange.setup(timeout)

See also

This method is called in the way illustrated above in BehaviourTree.

unregister_services()[source]

Use this method to make sure services are cleaned up when you wish to subsequently discard the Exchange instance. This should be a fairly atypical use case however - first consider if there are ways to modify trees on the fly instead of destructing/recreating all of the peripheral machinery.

py_trees_ros.blackboard.pickle_warning_message()[source]

Warning message for when the blackboard has unpicklable objects.

Returns:the warning message
Return type:str

py_trees_ros.conversions

Converter methods for transferring information back and forth between py_trees objects and ros messages.

py_trees_ros.conversions.behaviour_to_msg(behaviour)[source]

Convert a behaviour to a message.

Parameters:behaviour (Behaviour) – behaviour to convert
Returns:a ros message representation of a behaviour
Return type:Behaviour
py_trees_ros.conversions.behaviour_type_to_msg_constant(behaviour)[source]

Convert a behaviour class type to a message constant.

Parameters:behaviour (Behaviour) – investigate the type of this behaviour
Returns:from the type constants in Behaviour
Return type:uint8
py_trees_ros.conversions.blackbox_enum_to_msg_constant(blackbox_level)[source]

Convert a blackbox level enum to a message constant.

Parameters:blackbox_level (BlackboxLevel) – blackbox level of a behaviour
Returns:from the type constants in Behaviour
Return type:uint8
py_trees_ros.conversions.status_enum_to_msg_constant(status)[source]

Convert a status to a message constant.

Parameters:status (Status) – status enum of a behaviour
Returns:from the status constants in Behaviour
Return type:uint8

py_trees_ros.subscribers

ROS subscribers are asynchronous communication handles whilst py_trees are by their nature synchronous. They tick, pause, then tick again and provide an assumption that only one behaviour or function is running at any single moment. Firing off a subscriber callback in the middle of that synchronicity to write to a blackboard would break this assumption.

To get around that, subscriber behaviours run the ros callbacks in a background thread and constrain locking and a local cache inside the behaviour. Only in the update function is a cached variable unlocked and then permitted to be used or written to the blackboard.

class py_trees_ros.subscribers.CheckData(name='Check Data', topic_name='/foo', topic_type=None, variable_name='bar', expected_value=None, fail_if_no_data=False, fail_if_bad_comparison=False, comparison_operator=<built-in function eq>, clearing_policy=<ClearingPolicy.ON_INITIALISE: 1>)[source]

Bases: py_trees_ros.subscribers.Handler

Check a subscriber to see if it has received data.

It optionally checks whether that data, or part of it has a specific value.

Usage Patterns

Sequence Guard: RUNNING until there is a successful comparison

  • fail_if_no_data=False
  • fail_if_bad_comparison=False

Selector Priority Chooser: FAILURE until there is a successful comparison

  • fail_if_no_data=True
  • fail_if_bad_comparison=True
Parameters:
  • name (str) – name of the behaviour
  • topic_name (str) – name of the topic to connect to
  • topic_type (any) – class of the message type (e.g. std_msgs.msg.String)
  • variable_name (str) – name of the variable to check
  • expected_value (any) – expected value of the variable
  • fail_if_no_data (bool) – FAILURE instead of RUNNING if there is no data yet
  • fail_if_bad_comparison (bool) – FAILURE instead of RUNNING if comparison failed
  • comparison_operator (func) – one from the python operator module
  • clearing_policy (ClearingPolicy) – when to clear the data

Tip

Prefer ToBlackboard and the various blackboard checking behaviours instead. It will provide you with better introspection capability and less complex behaviour construction to manage.

update()[source]

Handles all the logic for determining what result should go back.

Returns:depending on the checking results
Return type:Status
class py_trees_ros.subscribers.EventToBlackboard(name='Event to Blackboard', topic_name='/event', variable_name='event')[source]

Bases: py_trees_ros.subscribers.Handler

Listen for events (std_msgs.msg.Empty) on a subscriber and writes the result to the blackboard.

This will write True if at least one message was received, False otherwise to a bool. This can then be consumed by the tree’s tick. No need to clean up, it will write anew on the next tick.

Tip

Ideally you need this at the very highest part of the tree so that it gets triggered every time - once this happens, then the rest of the behaviour tree can utilise the variables.

Parameters:
  • name (str) – name of the behaviour
  • topic_name (str) – name of the topic to connect to
  • variable_name (str) – name to write the boolean result on the blackboard
update()[source]

Check for data and write to the board.

class py_trees_ros.subscribers.Handler(name='Subscriber Handler', topic_name='/foo', topic_type=None, clearing_policy=<ClearingPolicy.ON_INITIALISE: 1>)[source]

Bases: py_trees.behaviour.Behaviour

Not intended for direct use, as this just absorbs the mechanics of setting up a subscriber for inheritance by user-defined behaviour classes. There are several options for the mechanism of clearing the data so that a new result can be processed.

Always Look for New Data

This will clear any currently stored data upon entry into the behaviour (i.e. when initialise() is called). This is useful for a behaviour in a sequence that is looking to start fresh as it is about to tick and be in a RUNNING state until new data arrives.

Look for New Data only after SUCCESS

This will clear any currently stored data as soon as the behaviour returns SUCCESS. This is useful for catching new triggers/events from things like buttons where you don’t want to miss things even though you may not actually be ticking.

Use the Latest Data

Even if this data was received before entry into the behaviour. In this case initialise() does not do anything with the currently stored data. Useful as a blocking behaviour to wait on some some topic having been initialised with some data (e.g. CameraInfo).

Warning

Do not use - it will always return INVALID. Subclass it to create a functional behaviour.

Parameters:
  • name (str) – name of the behaviour
  • topic_name (str) – name of the topic to connect to
  • topic_type (any) – class of the message type (e.g. std_msgs.msg.String)
  • clearing_policy (ClearingPolicy) – when to clear the data
initialise()[source]

If the clearing policy is set to ON_INITIALISE it will clear the internally saved message, otherwise it does nothing.

setup(timeout)[source]

Initialises the subscriber.

Parameters:timeout (float) – time to wait (0.0 is blocking forever)
Returns:whether it timed out trying to setup
Return type:bool
class py_trees_ros.subscribers.ToBlackboard(name='ToBlackboard', topic_name='chatter', topic_type=None, blackboard_variables={'chatter': None}, initialise_variables={}, clearing_policy=<ClearingPolicy.ON_INITIALISE: 1>)[source]

Bases: py_trees_ros.subscribers.Handler

Saves the latest message to the blackboard and immediately returns success. If no data has yet been received, this behaviour blocks (i.e. returns RUNNING).

Typically this will save the entire message, however sub fields can be designated, in which case they will write to the specified keys.

Parameters:
  • name (str) – name of the behaviour
  • topic_name (str) – name of the topic to connect to
  • topic_type (any) – class of the message type (e.g. std_msgs.msg.String)
  • blackboard_variables (dict) – blackboard variable string or dict {names (keys) - message subfields (values)}, use a value of None to indicate the entire message
  • initialise_variables (bool) – initialise the blackboard variables to some defaults
  • clearing_policy (ClearingPolicy) – when to clear the data

Examples

To capture an entire message:

chatter_to_blackboard = ToBlackboard(topic_name="chatter",
                                     topic_type=std_msgs.msg.String,
                                     blackboard_variables = {'chatter': None}
                                     )

or to get rid of the annoying sub-data field in std_msgs/String:

chatter_to_blackboard = ToBlackboard(topic_name="chatter",
                                     topic_type=std_msgs.msg.String,
                                     blackboard_variables = {'chatter': 'data'}
                                     )

combinations of multiple entities inside the message can also be saved:

blackboard_variables={"pose_with_covariance_stamped": None, "pose": "pose.pose"}
setup(timeout)[source]

Initialise the subscriber.

Parameters:timeout (float) – time to wait (0.0 is blocking forever)
Returns:whether it timed out trying to setup
Return type:bool
update()[source]

Writes the data (if available) to the blackboard.

Returns:RUNNING (no data) or SUCCESS
Return type:Status
class py_trees_ros.subscribers.WaitForData(name='Wait For Data', topic_name='chatter', topic_type=None, clearing_policy=<ClearingPolicy.ON_INITIALISE: 1>)[source]

Bases: py_trees_ros.subscribers.Handler

Waits for a subscriber’s callback to be triggered. This doesn’t care about the actual data, just whether it arrived or not, so is useful for catching triggers (std_msgs/Empty messages) or blocking (in the behaviour sense) until some data has arrived (e.g. camera configuration). There are two use cases:

Usage Patterns

Got Something, Sometime

  • clearing_policy == NEVER

Don’t care when data arrived, just that it arrived. This could be for something like a map topic, or a configuration that you need to block. Once it returns SUCCESS, it will always return SUCCESS.

Wating for the Next Thing, Starting From Now

  • clearing_policy == ON_INTIALISE

Useful as a gaurd at the start of a sequence, that is waiting for an event to trigger after the sequence has started (i.e. been initialised).

Wating for the Next Thing, Starting from the Last

  • clearing_policy == ON_SUCCESS

Useful as a guard watching for an event that could have come in anytime, but for which we do with to reset (and subsequently look for the next event). e.g. button events.

Parameters:
  • name (str) – name of the behaviour
  • topic_name (str) – name of the topic to connect to
  • topic_type (any) – class of the message type (e.g. std_msgs.msg.String)
  • clearing_policy (ClearingPolicy) – when to clear the data
update()[source]
Returns:RUNNING (no data) or SUCCESS
Return type:Status

py_trees_ros.trees

The ROS Behaviour Tree extends the core Behaviour Tree class with a few ROS style adornments. The major features currently include:

  • Publishers for ascii/dot tree visualisations and the blackboard
  • A publisher which dumps the entire tree at every change for the rqt plugin
  • Bagging of the tree for offline visualisation and debugging
class py_trees_ros.trees.BehaviourTree(root, record_rosbag=True)[source]

Bases: py_trees.trees.BehaviourTree

Extend the py_trees.trees.BehaviourTree class with a few bells and whistles for ROS:

  • ros publishers with snapshot ascii/dot graph views of the tree
  • ros publisher with data representation of the entire tree for monitoring/bagging
  • ros publisher showing what the current tip is
  • a blackboard exchange with introspection and watcher services
ROS Publishers:
  • ~ascii/tree (std_msgs.msg.String)
    • static view of the entire tree (debugging)
  • ~ascii/snapshot (std_msgs.msg.String)
    • runtime ascii snapshot view of the ticking tree (debugging)
  • ~dot/tree (std_msgs.msg.String)
    • static dot graph of the entire tree (debugging)
  • ~log/tree (py_trees_msgs.msg.BehaviourTree)
    • representation of the entire tree in message form for rqt/bagging
  • ~tip (py_trees_msgs.msg.Behaviour)
    • the tip of the tree after the last tick

See also

It also exposes publishers and services from the blackboard exchange in it’s private namespace. Refer to Exchange for details.

Parameters:
  • root (bool) – root node of the tree
  • root – whether the tree should record a rosbag itself or not
Raises:

AssertionError – if incoming root variable is not the correct type

setup(timeout)[source]

Setup the publishers, exechange and add ros-relevant pre/post tick handlers to the tree. Ultimately relays this call down to all the behaviours in the tree.

Parameters:timeout (float) – time to wait (0.0 is blocking forever)
Returns:suceess or failure of the operation
Return type:bool

py_trees.utilities

Assorted utility functions.

class py_trees_ros.utilities.Publishers(publishers, introspection_topic_name='publishers')[source]

Bases: object

Utility class that groups the publishers together in one convenient structure.

Parameters:(obj (publishers) – tuple): list of (str, str, bool, int) tuples representing (topic_name, publisher_type, latched, queue_size) specifications to create publishers with

Examples

Convert the incoming list of publisher name, type, latched, queue_size specifications into proper variables of this class.

publishers = rocon_python_comms.utils.Publishers(
    [
        ('~foo', std_msgs.String, True, 5),
        ('/foo/bar', std_msgs.String, False, 5),
        ('foobar', '/foo/bar', std_msgs.String, False, 5),
    ]
)

Note: ‘~/introspection/dude’ will become just ‘dude’ unless you prepend a field for the name as in the third example above.

class py_trees_ros.utilities.Subscribers(subscribers, introspection_topic_name='subscribers')[source]

Bases: object

Converts the incoming list of subscriber name, msg type, callback triples into proper variables of this class. Optionally you can prefix an arg that forces the name of the variable created.

Parameters:(obj (subscribers) – tuple): list of (str, str, bool, int) tuples representing (topic_name, subscriber_type, latched, queue_size) specifications to create subscribers with

Examples

subscribers = rocon_python_comms.utils.Subscribers(
    [
        ('~dudette', std_msgs.String, subscriber_callback),
        ('/dudette/jane', std_msgs.String, subscriber_callback),
        ('jane', /dudette/jane', std_msgs.String, subscriber_callback),
    ]
)

Note: ‘~/introspection/dude’ will become just ‘dude’ unless you prepend a field for the name as in the third example above.

py_trees_ros.utilities.basename(name)[source]

Generate the basename from a ros name.

Parameters:name (str) – ros name
Returns:name stripped up until the last slash or tilde character.
Return type:str

Examples

basename("~dude")
# 'dude'
basename("/gang/dude")
# 'dude'
py_trees_ros.utilities.publish_resolved_names(publisher, ros_communication_handles)[source]

Worker that provides a string representation of all the resolved names and publishes it so we can use it as an introspection topic in runtime.

Parameters:
  • publisher (rospy.Publisher) – use this object to publish with
  • ros_communication_handles ([]) – list of handles with their resolved names to to publish

py_trees.visitors

ROS Visitors are entities that can be passed to a ROS 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).

Warning

Visitors should not modify the behaviours they visit.

See also

The base interface and core visitors in py_trees.visitors

class py_trees_ros.visitors.LoggingVisitor[source]

Bases: py_trees.visitors.VisitorBase

Visits the entire tree and gathers all behaviours as messages for the tree logging publishers.

Variables:tree (py_trees_msgs.msg.BehaviourTree) – tree representation in message form
initialise()[source]

Initialise and stamp a py_trees_msgs.msg.BehaviourTree instance.

run(behaviour)[source]

Convert the behaviour into a message and appendd it to the tree.

Parameters:behaviour (Behaviour) – behaviour to convert
class py_trees_ros.visitors.SnapshotVisitor[source]

Bases: py_trees.visitors.VisitorBase

Visits the tree in tick-tock, recording runtime information for publishing the information as a snapshot view of the tree after the iteration has finished.

Variables:
  • nodes (dict) – dictionary of behaviour id (uuid.UUID) and status (Status) pairs
  • 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

This visitor should be used with the BehaviourTree class to collect information to publish for both bagging and the rqt monitoring plugin.

initialise()[source]

Switch running to previously running and then reset all other variables. This will 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

py_trees_ros.mock

This package contains mock nodes for ROS py_trees simulations.

py_trees_ros.mock.action_server

Mocks the move base action server of the ROS navigation stack.

class py_trees_ros.mock.action_server.ActionServer(action_name, action_type, worker, goal_received_callback=None, duration=None)[source]

Bases: object

Generic action server that can be subclassed to quickly create action servers of varying types in a mock simulation.

Dynamic Reconfigure:
  • ~duration (float)
    • reonfigure the duration to be used for the next goal execution
Parameters:
  • action_name (str) – name of the action server (e.g. move_base)
  • action_type (any) – type of the action server (e.g. move_base_msgs.msg.MoveBaseAction
  • worker (func) – callback to be executed inside the execute loop, no args
  • goal_recieved_callback (func) – callback to be executed immediately upon receiving a goal
  • duration (float) – forcibly override the dyn reconf time for a goal to complete (seconds)
__weakref__

list of weak references to the object (if defined)

dynamic_reconfigure_callback(config, unused_level)[source]
Parameters:
  • config (dynamic_reconfigure.encoding.Config) – incoming configuration
  • level (int) –
execute(goal)[source]

Check for pre-emption, but otherwise just spin around gradually incrementing a hypothetical ‘percent’ done.

Parameters:goal (any) – goal of type specified by the action_type in the constructor.
start()[source]

Start the action server.

py_trees_ros.mock.battery

Mocks a battery provider.

class py_trees_ros.mock.battery.Battery[source]

Mocks the processed battery state for a robot (/battery/sensor_state) as well as a possible charging source (/battery/charging_source).

ROS Publishers:
  • ~state (sensor_msgs.msg.BatteryState)
    • full battery state information
Dynamic Reconfigure:
  • ~charging_percentage (float)
    • one-step setting of the current battery percentage
  • ~charging (bool)
    • whether it is currently charging or not
  • ~charging_increment (float)
    • how fast it charges/discharges

On startup it is in a DISCHARGING state. Use rqt_reconfigure to change the battery state.

dynamic_reconfigure_callback(config, level)[source]

Don’t use the incoming config except as a read only tool. If we write variables, make sure to use the server’s update_configuration, which will trigger this callback here.

Parameters:
  • config (dynamic_reconfigure.encoding.Config) – incoming configuration
  • level (int) –
spin()[source]

Spin around, updating battery state and publishing the result.

py_trees_ros.mock.move_base

Mocks the move base action server of the ROS navigation stack.

class py_trees_ros.mock.move_base.MoveBase(odometry_topic='/odom', pose_topic='/pose', duration=None)[source]

Bases: py_trees_ros.mock.action_server.ActionServer

Simulates:

  • move base interface
  • publishing on /odom (nav_msgs.msg.Odometry)
  • publishing on /pose (geometry_msgs.msg.PoseWithCovarianceStamped)
Parameters:
  • odometry_topic (str) – name of the odometry topic
  • pose_topic (str) – name of the pose (with covariance stamped) topic
  • duration (int) – time for a goal to complete (seconds)
publish(unused_event)[source]

Most things expect a continous stream of odometry/pose messages, so we run this in a background thread.

worker()[source]

Increment the odometry and pose towards the goal.

py_trees_ros.mock.rotate

Mocks a simple action server that rotates the robot 360 degrees.

class py_trees_ros.mock.rotate.Rotate(rotation_rate=1.57)[source]

Bases: py_trees_ros.mock.action_server.ActionServer

Simple server that controls a full rotation of the robot.

Parameters:rotation_rate (float) – rate of rotation )rad/s)
worker()[source]

Create some appropriate feedback.

py_trees_ros.tutorials

Entry points to the tutorials

py_trees_ros.tutorials.behaviours

A few behaviours to support the tutorials.

class py_trees_ros.tutorials.behaviours.FlashLedStrip(name, topic_name='/led_strip/command', colour='red')[source]

Bases: py_trees.behaviour.Behaviour

This behavoiur simply shoots a command off to the LEDStrip to flash a certain colour and returns RUNNING. Note that this behaviour will never return with SUCCESS but will send a clearing command to the LEDStrip if it is cancelled or interrupted by a higher priority behaviour.

Parameters:
  • name (str) – name of the behaviour
  • topic_name (str) – name of the battery state topic
  • colour (str) – colour to flash [‘red’, ‘green’, blue’]
setup(timeout)[source]
Parameters:timeout (float) – time to wait (0.0 is blocking forever)
Returns:whether it timed out trying to setup
Return type:bool
terminate(new_status)[source]

Shoot off a clearing command to the led strip.

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

Annoy the led strip to keep firing every time it ticks over (the led strip will clear itself if no command is forthcoming within a certain period of time). This behaviour will only finish if it is terminated or interrupted from above.

class py_trees_ros.tutorials.behaviours.ScanContext(name)[source]

Bases: py_trees.behaviour.Behaviour

This behavoiur simply shoots a command off to the LEDStrip to flash a certain colour and returns RUNNING. Note that this behaviour will never return with SUCCESS but will send a clearing command to the LEDStrip if it is cancelled or interrupted by a higher priority behaviour.

Parameters:name (str) – name of the behaviour
initialise()[source]

Get various dyn reconf configurations and cache/set the new variables.

setup(timeout)[source]

Try and connect to the dynamic reconfigure server on the various namespaces.

terminate(new_status)[source]

Regardless of whether it succeeed or failed or is getting set to invalid we have to be absolutely sure to reset the navi context.

py_trees_ros.tutorials.jobs

A few behaviours to support the tutorials.

class py_trees_ros.tutorials.jobs.Scan[source]

Bases: object

A job handler that instantiates a subtree for scanning to be executed by a behaviour tree.

__init__()[source]

Tune into a channel for incoming goal requests. This is a simple subscriber here but more typically would be a service or action interface.

__weakref__

list of weak references to the object (if defined)

create_report_string(subtree_root)[source]

Introspect the subtree root to determine an appropriate human readable status report string.

Parameters:subtree_root (Behaviour) – introspect the subtree
Returns:human readable substring
Return type:str
static create_root(goal=)[source]

Create the job subtree based on the incoming goal specification.

Parameters:goal (Empty) – incoming goal specification
Returns:subtree root
Return type:Behaviour
goal

Getter for the variable indicating whether or not a goal has recently been received but not yet handled. It simply makes sure it is wrapped with the appropriate locking.

incoming(msg)[source]

Incoming goal callback.

Parameters:msg (Empty) – incoming goal message

py_trees_ros.tutorials.qt

Qt support for the tutorials.