py_trees_ros_tutorials.mock.actions module

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 = 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.command_line_argument_parser()[source]
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.