Controller Handler¶
This handler allows you to easily turn on ROS controllers, and ensure other controllers get turned off when necessary.
-
class
controller_handler.
ControllerHandler
(robot_name, debug=False)¶ Handle ROS controllers
- Parameters
robot_name (str) – Name of the robot
-
get_controller_list
()¶ Get the list of currently loaded controllers
- Returns
controllers – List of controllers
- Return type
list
-
get_controllers_with_state
(states=None)¶ Get a list of controllers that have a particular state
- Parameters
states (list or str) – List of states (or s single state) to check for (
uninitialized
,initialized
,running
,stopped
,waiting
,aborted
,unknown
)- Returns
controllers – List of controller names matching the states
- Return type
list
-
load_controller
(controller)¶ Load a ROS controller
- Parameters
controller (str) – Name of the controller to load
- Returns
response – Service response from the controller manager
- Return type
str
-
play_program
()¶ Start the program on the teach pendant. This ony works if you are in remote control mode
- Returns
result – The result of the service call
- Return type
srv
-
set_controller
(controller)¶ Set which ROS controller is started, and stop all others
- Parameters
controller (str) – Name of the controller to start
- Returns
response – Service response from the controller manager
- Return type
str
-
set_reserved_controllers
(controllers)¶ Set which controllers are reserved (always running)
- Parameters
controllers (list) – List of controller names
-
set_speed_slider
(fraction)¶ Set the speed slider fraction
- Parameters
fraction (float) – Slider fraction to set (0.02 to 1.00)
- Returns
result – The result of the service call
- Return type
srv
-
stop_program
()¶ Stop the program on the teach pendant. This ony works if you are in remote control mode
- Returns
result – The result of the service call
- Return type
srv
-
switch_controller
(start_controllers, stop_controllers, strictness=1, start_asap=False, timeout=0)¶ Switch ROS controllers
- Parameters
start_controllers (list) – Names of the controllers to start
stop_controllers (list) – Names of the controllers to stop
strictness (int) – Strictness of controller switching
start_asap (bool) – Decide whether controllers should be started immediately
timeout (int) – Timeout (in seconds)
- Returns
response – Service response from the controller manager
- Return type
str
-
unload_controller
(controller)¶ Unload a ROS controller
- Parameters
controller (str) – Name of the controller to unload
- Returns
response – Service response from the controller manager
- Return type
str
-
update_controller_list
()¶ Update the controller list via a ROS service call.