panda_gazebo.core.control_switcher

This class is responsible for switching the control type that is used for controlling the Panda Robot robot arm and hand. It serves as a wrapper around the services created by the ROS controller_manager class.

Control types:

Module Contents

Classes

ControllerSwitcherResponse

Class used for returning the result of the PandaControlSwitcher.switch()

PandaControlSwitcher

Used for switching the Panda robot controllers.

Attributes

ARM_CONTROLLERS

HAND_CONTROLLERS

CONTROLLER_DICT

panda_gazebo.core.control_switcher.ARM_CONTROLLERS[source]
panda_gazebo.core.control_switcher.HAND_CONTROLLERS[source]
panda_gazebo.core.control_switcher.CONTROLLER_DICT[source]
class panda_gazebo.core.control_switcher.ControllerSwitcherResponse(success=True, prev_control_type='')[source]

Class used for returning the result of the PandaControlSwitcher.switch() method.

success

Specifies whether the switch operation was successful.

Type:

bool

prev_control_type

The previous used control type.

Type:

str

Initialise ControllerSwitcherResponse object.

Parameters:
  • success (bool, optional) – Whether the switch operation was successful. Defaults to True.

  • prev_control_type (str, optional) – The previous used control type. Defaults to "".

class panda_gazebo.core.control_switcher.PandaControlSwitcher(connection_timeout=10, verbose=True, robot_name_space='')[source]

Bases: object

Used for switching the Panda robot controllers.

verbose

Boolean specifying whether we want to display log messages during switching.

Type:

bool

arm_control_types[source]

List of currently active arm control types.

Type:

list

hand_control_types[source]

List of currently active hand control types.

Type:

list

Initialise PandaControlSwitcher object.

Parameters:
  • connection_timeout (str, optional) – The timeout for connecting to the controller_manager services. Defaults to 10 sec.

  • verbose (bool, optional) – Whether to display debug log messages. Defaults to True.

  • robot_name_space (string, optional) – The namespace the robot, and thus the ‘controller_manager’ is on. Defaults to "".

property arm_control_types[source]

Returns the currently active arm control types. Returns empty list when no control type is enabled.

property hand_control_types[source]

Returns the currently active hand control types. Returns empty when no control type is enabled.

wait_for_control_type(control_group, control_type, timeout=None, rate=10)[source]

Function that can be used to wait till all the controllers used for a given ‘control_group’ and ‘control_type’ are running. Useful four when you expect a launch file to load certain controllers.

Parameters:
  • control_group (str) – The control group of which you want the switch the control type. Options are hand or arm.

  • control_type (str) – The robot control type you want to switch to for the given ‘control_group’. Options are: trajectory, position and effort.

  • timeout (float, optional) – The function timeout. Defaults to None meaning the function will wait for ever.

  • rate (int, optional) – The ‘control_type’ check rate. Defaults to 10 hz.

Raises:

TimeoutError – Thrown when the set timeout has passed.

switch(control_group, control_type, load_controllers=True, timeout=3, verbose=None)[source]

Switch Panda robot control type. This function stops all currently running controllers and starts the required controllers for a given control type.

Parameters:
  • control_group (str) – The control group of which you want the switch the control type. Options are hand or arm.

  • control_type (str) – The robot control type you want to switch to for the given ‘control_group’. Options are: trajectory, position and effort.

  • load_controllers (bool) – Try to load the required controllers for a given control_type if they are not yet loaded.

  • timeout (int, optional) – The timeout for switching to a given controller. Defaults to 3 sec.

  • verbose (bool, optional) – Whether to display debug log messages. Defaults to verbose value set during the class initiation.

Returns:

Contains information about whether the switch operation was successful ‘success’ and the previously used controller ‘prev_control_type’.

Return type:

ControllerSwitcherResponse