Module API

py_trees_ros_tutorials

py_trees_ros_tutorials.behaviours

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).

py_trees_ros_tutorials.mock

py_trees_ros_tutorials.mock.actions

Action servers and clients

class py_trees_ros_tutorials.mock.actions.DockClient[source]

Bases: GenericClient

A mock docking controller client.

class py_trees_ros_tutorials.mock.actions.GenericClient(node_name: str, action_name: str, action_type: Any, generate_feedback_message: Callable[[Any], str] = None)[source]

Bases: object

Generic action client that can be used to test the mock action servers.

Parameters:
  • node_name – name to use when creating the node for this process

  • action_name – the action namespace under which topics and services exist (e.g. move_base)

  • action_type – the action type (e.g. move_base_msgs.msg.MoveBaseAction)

  • generate_feedback_message – format the feedback message

cancel_response_callback(future: rclpy.task.Future)[source]

Cancel response callback

Parameters:

future – details returning from the server about the cancel request

feedback_callback(msg: Any)[source]

Prints the feedback on the node’s logger.

Parameters:

msg – the feedback message, particular to the action type definition

get_result_callback(future: rclpy.task.Future)[source]

Finally, at the end of the pipeline, what was the result!?

Parameters:

future – details returning from the server about the goal result

goal_response_callback(future: rclpy.task.Future)[source]

Handle goal response, proceed to listen for the result if accepted.

Parameters:

future – details returning from the server about the goal request

send_cancel_request()[source]

Start the cancel request, chain it to cancel_response_callback().

send_goal() rclpy.task.Future[source]

Send the goal and get a future back, but don’t do any spinning here to await the future result. Chain it to goal_response_callback().

Returns:

the future awaits…

Return type:

rclpy.task.Future

setup()[source]

Middleware communications setup. This uses a hard coded default of 2.0 seconds to wait for discovery of the action server. If it should fail, it raises a timed out error.

Raises:

py_trees_ros.exceptions.TimedOutError

shutdown()[source]

Shutdown, cleanup.

spin(cancel: bool = False)[source]

Common spin method for clients.

Parameters:

cancel – send a cancel request shortly after sending the goal request

class py_trees_ros_tutorials.mock.actions.MoveBaseClient[source]

Bases: GenericClient

A mock move base client.

class py_trees_ros_tutorials.mock.actions.RotateClient[source]

Bases: GenericClient

A mock rotation controller client.

py_trees_ros_tutorials.mock.actions.dock_client()[source]

Spin up a docking client and manage it from init to shutdown. Some customisation possible via the command line arguments.

py_trees_ros_tutorials.mock.actions.move_base_client(args=None)[source]

Spin up a move base client and manage it from init to shutdown.

py_trees_ros_tutorials.mock.actions.rotate_client(args=None)[source]

Spin up a rotation client and manage it from init to shutdown.

py_trees_ros_tutorials.mock.battery

Mock the state of a battery component.

class py_trees_ros_tutorials.mock.battery.Battery[source]

Bases: object

Mocks the processed battery state for a robot (/battery/sensor_state).

Node Name:
  • battery

Publishers:
  • ~state (sensor_msgs.msg.BatteryState)

    • full battery state information

Dynamic Parameters:
  • ~charging_percentage (float)

    • one-shot setter of the current battery percentage

  • ~charging (bool)

    • charging or discharging

  • ~charging_increment (float)

    • the current charging/discharging increment

On startup it is in a DISCHARGING state and updates every 200ms. Use the dashboard to dynamically reconfigure parameters.

shutdown()[source]

Cleanup ROS components.

update_and_publish()[source]

Timer callback that processes the battery state update and publishes.

py_trees_ros_tutorials.mock.battery.main()[source]

Entry point for the mock batttery node.

py_trees_ros_tutorials.mock.dock

Mocks a docking controller

class py_trees_ros_tutorials.mock.dock.Dock(*args: Any, **kwargs: Any)[source]

Bases: GenericServer

Simple action server that docks/undocks depending on the instructions in the goal requests.

Node Name:
  • docking_controller

Action Servers:
  • /dock (py_trees_ros_interfaces.action.Dock)

    • docking/undocking control

Parameters:

duration – mocked duration of a successful docking/undocking action

generate_feedback_message() py_trees_ros_interfaces.action.Dock.Feedback[source]

Create a feedback message that populates the percent completed.

Returns:

the populated feedback message

Return type:

py_trees_actions.Dock_Feedback

goal_received_callback(goal)[source]

Set the title of the action depending on whether a docking or undocking action was requestions (‘Dock’/’UnDock’)

py_trees_ros_tutorials.mock.dock.main()[source]

Entry point for the mocked docking controller.

py_trees_ros_tutorials.mock.launch

py_trees_ros_tutorials.mock.led_strip

py_trees_ros_tutorials.mock.move_base

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

class py_trees_ros_tutorials.mock.move_base.MoveBase(*args: Any, **kwargs: Any)[source]

Bases: GenericServer

Simulates a move base style interface.

Node Name:
  • move_base_controller

Action Servers:
  • /move_base (py_trees_ros_interfaces.action.MoveBase)

    • point to point move base action

Parameters:

duration – mocked duration of a successful action

generate_feedback_message() py_trees_ros_interfaces.action.MoveBase.Feedback[source]

Do a fake pose incremenet and populate the feedback message.

Returns:

the populated feedback message

Return type:

py_trees_actions.MoveBase.Feedback

py_trees_ros_tutorials.mock.move_base.main()[source]

Entry point for the mock move base node.

py_trees_ros_tutorials.mock.rotate

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

class py_trees_ros_tutorials.mock.rotate.Rotate(*args: Any, **kwargs: Any)[source]

Bases: GenericServer

Simple server that controls a full rotation of the robot.

Node Name:
  • rotation_controller

Action Servers:
  • /rotate (py_trees_ros_interfaces.action.Dock)

    • motion primitives - rotation server

Parameters:

rotation_rate (float) – rate of rotation (rad/s)

generate_feedback_message()[source]

Create a feedback message that populates the percent completed.

Returns:

the populated feedback message

Return type:

py_trees_actions.Rotate.Feedback

py_trees_ros_tutorials.mock.rotate.main()[source]

Entry point for the mock rotation controller node.

py_trees_ros_tutorials.mock.safety_sensors

py_trees_ros_tutorials.version