pyrcf.components.ctrl_loop_debuggers

Module containing interface and definitions of control loop debuggers that can be used in the control loop.

Submodules

Classes

CtrlLoopDebuggerBase

Base class for control loop debuggers. Can only be used with control loops.

DummyDebugger

A dummy debugger to test in pipeline.

ComponentDataRecorderDebugger

A data recording debugger that records all the control loop data directly to a file. Use

ComponentDataPublisherDebugger

This control loop debugger will stream the data from all the components in the control loop

PlotjugglerLoopDebugger

This control loop debugger will stream the data from all the components in the control loop

PybulletRobotPlanDebugger

This control loop debugger will create a dummy visual robot in pybullet which

PybulletRobotStateDebugger

This control loop debugger will create a dummy visual robot in pybullet which

Package Contents

class pyrcf.components.ctrl_loop_debuggers.CtrlLoopDebuggerBase(rate: float = None, clock: pyrcf.utils.time_utils.ClockBase = PythonPerfClock())

Bases: abc.ABC

Base class for control loop debuggers. Can only be used with control loops.

_rate
_should_run()
run_once(t: float, dt: float, robot_state: pyrcf.core.types.RobotState, global_plan: pyrcf.core.types.GlobalMotionPlan, agent_outputs: List[Tuple[pyrcf.core.types.LocalMotionPlan, pyrcf.core.types.RobotCmd]], robot_cmd: pyrcf.core.types.RobotCmd)

The main method that will be run in every control loop.

NOTE: SHOULD NOT BE OVERRIDDEN. Override the _run_once_impl method.

This method automatically checks if it is ok to trigger the implemented child method, and calls it if appropriate.

Parameters:
  • t (float) – Current time in the control loop.

  • dt (float) – The current dt in the control loop.

  • robot_state (RobotState) – robot state after update from the state estimator in the control loop.

  • global_plan (GlobalMotionPlan) – The global plan output produced by the global planner.

  • agent_outputs (List[Tuple[LocalMotionPlan, RobotCmd]]) – The list of outputs from all agents in the control loop.

  • robot_cmd (RobotCmd) – The final command written to the robot.

abstract _run_once_impl(t: float, dt: float, robot_state: pyrcf.core.types.RobotState, global_plan: pyrcf.core.types.GlobalMotionPlan, agent_outputs: List[Tuple[pyrcf.core.types.LocalMotionPlan, pyrcf.core.types.RobotCmd]], robot_cmd: pyrcf.core.types.RobotCmd)

The main method that will be run in every control loop. Should be overridden in the implemented child of CtrlLoopDebuggerBase.

This method will be called automatically if the timer is triggered, as long as the main run_once() method is called continuously in the control loop.

Parameters:
  • t (float) – Current time in the control loop.

  • dt (float) – The current dt in the control loop.

  • robot_state (RobotState) – robot state after update from the state estimator in the control loop.

  • global_plan (GlobalMotionPlan) – The global plan output produced by the global planner.

  • agent_outputs (List[Tuple[LocalMotionPlan, RobotCmd]]) – The list of outputs from all agents in the control loop.

  • robot_cmd (RobotCmd) – The final command written to the robot.

shutdown()

Cleanly shutdown the debugger. Override in child class if required. The base class implements an empty function.

class pyrcf.components.ctrl_loop_debuggers.DummyDebugger(squawk: bool = True, rate: float = 10, clock: pyrcf.utils.time_utils.ClockBase = PythonPerfClock())

Bases: CtrlLoopDebuggerBase

A dummy debugger to test in pipeline.

_squawk
_run_once_impl(t: float, dt: float, robot_state: pyrcf.core.types.RobotState, global_plan: pyrcf.core.types.GlobalMotionPlan, agent_outputs: List[Tuple[pyrcf.core.types.LocalMotionPlan | pyrcf.core.types.RobotCmd]], robot_cmd: pyrcf.core.types.RobotCmd)

The main method that will be run in every control loop. Should be overridden in the implemented child of CtrlLoopDebuggerBase.

This method will be called automatically if the timer is triggered, as long as the main run_once() method is called continuously in the control loop.

Parameters:
  • t (float) – Current time in the control loop.

  • dt (float) – The current dt in the control loop.

  • robot_state (RobotState) – robot state after update from the state estimator in the control loop.

  • global_plan (GlobalMotionPlan) – The global plan output produced by the global planner.

  • agent_outputs (List[Tuple[LocalMotionPlan, RobotCmd]]) – The list of outputs from all agents in the control loop.

  • robot_cmd (RobotCmd) – The final command written to the robot.

class pyrcf.components.ctrl_loop_debuggers.ComponentDataRecorderDebugger(file_name: str, rate: float = None, clock: pyrcf.utils.time_utils.ClockBase = PythonPerfClock(), extra_data_callables: Callable[[], Any] | List[Callable[[], Any]] = None, buffer_size: int = 50)

Bases: pyrcf.components.ctrl_loop_debuggers.ctrl_loop_debugger_base.CtrlLoopDebuggerBase

A data recording debugger that records all the control loop data directly to a file. Use ComponentDataRecorderDataParser from pyrcf.utils.data_io_utils to parse the recorded data file.

NOTE: if your computer has enough RAM and compute power, this debugger is better (in terms of keeping desired control loop rate) than ComponentDataPublisherDebugger.

_file
_additional_handles = []
_buffer = []
_buffer_size
_run_once_impl(t: float, dt: float, robot_state: pyrcf.core.types.RobotState, global_plan: pyrcf.core.types.GlobalMotionPlan, agent_outputs: List[Tuple[pyrcf.core.types.LocalMotionPlan, pyrcf.core.types.RobotCmd]], robot_cmd: pyrcf.core.types.RobotCmd)

The main method that will be run in every control loop. Should be overridden in the implemented child of CtrlLoopDebuggerBase.

This method will be called automatically if the timer is triggered, as long as the main run_once() method is called continuously in the control loop.

Parameters:
  • t (float) – Current time in the control loop.

  • dt (float) – The current dt in the control loop.

  • robot_state (RobotState) – robot state after update from the state estimator in the control loop.

  • global_plan (GlobalMotionPlan) – The global plan output produced by the global planner.

  • agent_outputs (List[Tuple[LocalMotionPlan, RobotCmd]]) – The list of outputs from all agents in the control loop.

  • robot_cmd (RobotCmd) – The final command written to the robot.

shutdown()

Cleanly shutdown the debugger. Override in child class if required. The base class implements an empty function.

class pyrcf.components.ctrl_loop_debuggers.ComponentDataPublisherDebugger(rate: float = None, clock: pyrcf.utils.time_utils.ClockBase = PythonPerfClock(), debug_publish_callables: Callable[[], Any] | List[Callable[[], Any]] = None, port: int = DEFAULT_ZMQ_PUBLISH_PORT)

Bases: pyrcf.components.ctrl_loop_debuggers.ctrl_loop_data_publisher_base.CtrlLoopDataPublisherBase

This control loop debugger will stream the data from all the components in the control loop so that it can be subscribed to by a zmq subscriber (see PyRCFSubscriberZMQ).

class pyrcf.components.ctrl_loop_debuggers.PlotjugglerLoopDebugger(rate: float = None, clock: pyrcf.utils.time_utils.ClockBase = PythonPerfClock(), debug_publish_callables: Callable[[], Any] | List[Callable[[], Any]] = None, port: int = DEFAULT_PLOTJUGGLER_PUBLISH_PORT)

Bases: ComponentDataPublisherDebugger

This control loop debugger will stream the data from all the components in the control loop so that it can be visualised in plotjuggler.

class pyrcf.components.ctrl_loop_debuggers.PybulletRobotPlanDebugger(urdf_path: str, rate: float = None, clock: pyrcf.utils.time_utils.ClockBase = PythonPerfClock(), cid: int = 0, enable_toggle_button: bool = True, show_ee_targets: bool = True, use_curr_pose_if_plan_unavailable: bool = True, **pybullet_debug_robot_kwargs)

Bases: pyrcf.components.ctrl_loop_debuggers.ctrl_loop_debugger_base.CtrlLoopDebuggerBase

This control loop debugger will create a dummy visual robot in pybullet which will try to follow position/pose plan in the control loop. This can be used to visualise ideal robot poses/configurations and to compare performance of controllers in tracking them.

_debugger_robot
_toggler_button = None
_show_ee_targets
_ee_frame_viz: Mapping[str, pyrcf.components.callback_handlers.pb_gui_utils.PybulletDebugFrameViz]
_use_curr_pose
_run_once_impl(t: float, dt: float, robot_state: pyrcf.core.types.RobotState, global_plan: pyrcf.core.types.GlobalMotionPlan, agent_outputs: List[Tuple[pyrcf.core.types.LocalMotionPlan, pyrcf.core.types.RobotCmd]], robot_cmd: pyrcf.core.types.RobotCmd)

The main method that will be run in every control loop. Should be overridden in the implemented child of CtrlLoopDebuggerBase.

This method will be called automatically if the timer is triggered, as long as the main run_once() method is called continuously in the control loop.

Parameters:
  • t (float) – Current time in the control loop.

  • dt (float) – The current dt in the control loop.

  • robot_state (RobotState) – robot state after update from the state estimator in the control loop.

  • global_plan (GlobalMotionPlan) – The global plan output produced by the global planner.

  • agent_outputs (List[Tuple[LocalMotionPlan, RobotCmd]]) – The list of outputs from all agents in the control loop.

  • robot_cmd (RobotCmd) – The final command written to the robot.

shutdown()

Cleanly shutdown the debugger. Override in child class if required. The base class implements an empty function.

classmethod fromBulletRobotInstance(robot: pyrcf.components.robot_interfaces.simulation.pybullet_robot.PybulletRobot, rate: float = None, clock: pyrcf.utils.time_utils.ClockBase = PythonPerfClock(), enable_toggle_button: bool = True, show_ee_targets: bool = True, use_curr_pose_if_plan_unavailable: bool = True, **pybullet_debug_robot_kwargs) PybulletRobotPlanDebugger

Creates an instance of PybulletRobotPlanDebugger using the provided PybulletRobot child class object.

Parameters:
  • robot (PybulletRobot) – The robot instance (will not be modified).

  • rate (float, optional) – Rate at which this should be triggered. Defaults to None (i.e. use control loop rate).

  • clock (ClockBase, optional) – The clock to use for timer. Defaults to PythonPerfClock().

  • cid (int, optional) – The pybullet physics client ID to connect to. Defaults to 0.

  • enable_toggle_button (bool, optional) – If set to True, this will create a button in the pybullet GUI to enable/disable the VISUALISATION of this debugger. Defaults to True. NOTE: This only affects the visualisation! Does not disable the actual debugger. NOTE: There can be an overhead when the visualisation is toggled on and off.

  • **pybullet_debug_robot_kwargs – Additional keyword arguments can be passed here. All keyword arguments to PybulletDebugRobot is allowed here (e.g. use rgba=[,,,] for setting the visualisation color of this debug robot)

Returns:

PybulletRobotPlanDebugger instance created using the urdf and

cid from the passed PybulletRobot object.

Return type:

PybulletRobotPlanDebugger

class pyrcf.components.ctrl_loop_debuggers.PybulletRobotStateDebugger(urdf_path: str, rate: float = None, clock: pyrcf.utils.time_utils.ClockBase = PythonPerfClock(), cid: int = 0, enable_toggle_button: bool = True, **bullet_debug_robot_kwargs)

Bases: pyrcf.components.ctrl_loop_debuggers.ctrl_loop_debugger_base.CtrlLoopDebuggerBase

This control loop debugger will create a dummy visual robot in pybullet which will simply mimic the joint states and base pose read from the robot_state (after passing through the state estimator update). This class can be used to visualise the robot states being read when the robot is running outside pybullet (e.g. real robot or remote).

_debugger_robot
_toggler_button = None
_run_once_impl(t: float, dt: float, robot_state: pyrcf.core.types.RobotState, global_plan: pyrcf.core.types.GlobalMotionPlan, agent_outputs: List[Tuple[pyrcf.core.types.LocalMotionPlan, pyrcf.core.types.RobotCmd]], robot_cmd: pyrcf.core.types.RobotCmd)

The main method that will be run in every control loop. Should be overridden in the implemented child of CtrlLoopDebuggerBase.

This method will be called automatically if the timer is triggered, as long as the main run_once() method is called continuously in the control loop.

Parameters:
  • t (float) – Current time in the control loop.

  • dt (float) – The current dt in the control loop.

  • robot_state (RobotState) – robot state after update from the state estimator in the control loop.

  • global_plan (GlobalMotionPlan) – The global plan output produced by the global planner.

  • agent_outputs (List[Tuple[LocalMotionPlan, RobotCmd]]) – The list of outputs from all agents in the control loop.

  • robot_cmd (RobotCmd) – The final command written to the robot.

shutdown()

Cleanly shutdown the debugger. Override in child class if required. The base class implements an empty function.

classmethod fromBulletRobotInstance(robot: pyrcf.components.robot_interfaces.simulation.pybullet_robot.PybulletRobot, rate: float = None, clock: pyrcf.utils.time_utils.ClockBase = PythonPerfClock(), enable_toggle_button: bool = True, **bullet_debug_robot_kwargs) PybulletRobotStateDebugger

Creates an instance of PybulletRobotStateDebugger using an existing PybulletRobot child class object.

Parameters:
  • robot (PybulletRobot) – The robot instance (will not be modified).

  • rate (float, optional) – Rate at which this should be triggered. Defaults to None (i.e. use control loop rate).

  • clock (ClockBase, optional) – The clock to use for timer. Defaults to PythonPerfClock().

  • cid (int, optional) – The pybullet physics client ID to connect to. Defaults to 0.

  • enable_toggle_button (bool, optional) – If set to True, this will create a button in the pybullet GUI to enable/disable the VISUALISATION of this debugger. Defaults to True. NOTE: This only affects the visualisation! Does not disable the actual debugger. NOTE: There can be an overhead when the visualisation is toggled on and off.

  • **bullet_debug_robot_kwargs – Additional keyword arguments can be passed here. All keyword arguments to PybulletDebugRobot is allowed here (e.g. use rgba=[,,,] for setting the visualisation color of this debug robot)

Returns:

PybulletRobotStateDebugger instance created using the urdf and

cid from the passed robot object.

Return type:

PybulletRobotStateDebugger