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 withSUCCESS
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’]
- 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 interminate()
.- 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.
- 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 returnRUNNING
).
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
- 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.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:
On startup it is in a DISCHARGING state and updates every 200ms. Use the
dashboard
to dynamically reconfigure parameters.
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
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
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)