py_trees_ros_tutorials.behaviours module

Behaviours for the tutorials.

class py_trees_ros_tutorials.behaviours.FlashLedStrip(*args: Any, **kwargs: Any)[source]

Bases: Behaviour

This behaviour 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.

Publishers:
  • /led_strip/command (std_msgs.msg.String)

    • colourised string command for the led strip [‘red’, ‘green’, ‘blue’]

Parameters:
  • name – name of the behaviour

  • topic_name – name of the battery state topic

  • colour – colour to flash [‘red’, ‘green’, blue’]

setup(**kwargs)[source]

Setup the publisher which will stream commands to the mock robot.

Parameters:

**kwargs (dict) – look for the ‘node’ object being passed down from the tree

Raises:

KeyError – if a ros2 node isn’t passed under the key ‘node’ in kwargs

terminate(new_status: py_trees.common.Status)[source]

Shoot off a clearing command to the led strip.

Parameters:

new_status – the behaviour is transitioning to this new status

update() py_trees.common.Status[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 priority interrupted from above.

Returns:

Always returns RUNNING

class py_trees_ros_tutorials.behaviours.ScanContext(*args: Any, **kwargs: Any)[source]

Bases: Behaviour

Alludes to switching the context of the runtime system for a scanning action. Technically, it reaches out to the mock robots safety sensor dynamic parameter, switches it off in initialise() and maintains that for the the duration of the context before returning it to it’s original value in terminate().

Parameters:

name (str) – name of the behaviour

initialise()[source]

Reset the cached context and trigger the chain of get/set parameter calls involved in changing the context.

Note

Completing the chain of service calls here (with rclpy.spin_until_future_complete(node, future)) is not possible if this behaviour is encapsulated inside, e.g. a tree tick activated by a ros2 timer callback, since it is already part of a scheduled job in a spinning node. It will just deadlock.

Prefer instead to chain a sequence of events that will be completed over a span of ticks instead of at best, blocking here and at worst, falling into deadlock.

setup(**kwargs)[source]

Setup the ros2 communications infrastructure.

Parameters:

**kwargs (dict) – look for the ‘node’ object being passed down from the tree

Raises:

KeyError – if a ros2 node isn’t passed under the key ‘node’ in kwargs

terminate(new_status: py_trees.common.Status)[source]

Reset the parameters back to their original (cached) values.

Parameters:

new_status – the behaviour is transitioning to this new status

update() py_trees.common.Status[source]

Complete the chain of calls begun in initialise() and then maintain the context (i.e. py_trees.behaviour.Behaviour and return RUNNING).