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
Class used for returning the result of the |
|
Used for switching the Panda robot controllers. |
Attributes
- class panda_gazebo.core.control_switcher.ControllerSwitcherResponse(success=True, prev_control_type='')[source]
Class used for returning the result of the
PandaControlSwitcher.switch()
method.Initialise ControllerSwitcherResponse object.
- 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.
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
orarm
.control_type (str) – The robot control type you want to switch to for the given ‘control_group’. Options are:
trajectory
,position
andeffort
.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
orarm
.control_type (str) – The robot control type you want to switch to for the given ‘control_group’. Options are:
trajectory
,position
andeffort
.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: