ros_controllers
Functions related to the handling of the start, stop, reset, load, unload, etc, of ROS controllers.
- ros_controllers.load_controller_srv(controller_name, ns=None, max_retries=5) bool [source]
Function to load a controller on the namespace.
- Parameters
controller_name (string) – name of the controller to load
ns (string) – namespace
max_retries (int) – number of retries to load the controller.
- Returns
true if the controller is loaded.
- Return type
bool
- ros_controllers.load_controller_list_srv(controller_list, ns=None, max_retries=5) None [source]
Function to load a list of controllers on the namespace.
- Parameters
controller_list (list of strings) – list of controllers to load
ns (string) – namespace
max_retries (int) – number of retries to load the controller.
- ros_controllers.unload_controller_srv(controller_name, ns=None, max_retries=5) bool [source]
Function to unload a controller on the namespace.
- Parameters
controller_name (string) – name of the controller to unload
ns (string) – namespace
max_retries (int) – number of retries to unload the controller.
- Returns
true if the controller is unloaded.
- Return type
bool
- ros_controllers.unload_controller_list_srv(controller_list, ns=None, max_retries=5) None [source]
Function to unload a list of controllers on the namespace.
- Parameters
controller_list (list of strings) – list of controllers to unload
ns (string) – namespace
max_retries (int) – number of retries to unload the controller.
- ros_controllers.switch_controllers_srv(start_controllers, stop_controllers, ns=None, strictness=1, start_asap=False, timeout=3.0, max_retries=5) bool [source]
Function to switch controllers on the namespace.
- Parameters
start_controllers (list of strings) – list of controllers to start
stop_controllers (list of strings) – list of controllers to stop
ns (string) – namespace
strictness (int) – strictness of the controller manager: BEST_EFFORT or STRICT (1 and 2, respectively).
start_asap (bool) – start the controllers as soon as their hardware dependencies are ready, will wait for all interfaces to be ready otherwise.
timeout (float) – the timeout in seconds before aborting pending controllers. Zero for infinite.
max_retries (int) – number of retries to switch the controller.
- Returns
true if the operation is successful.
- Return type
bool
- ros_controllers.start_controllers_srv(start_controllers, ns=None, strictness=1, start_asap=False, timeout=3.0) bool [source]
Function to start controllers on the namespace.
- Parameters
start_controllers (list of strings) – list of controllers to start
ns (string) – namespace
strictness (int) – strictness of the controller manager: BEST_EFFORT or STRICT (1 and 2, respectively).
start_asap (bool) – start the controllers as soon as their hardware dependencies are ready, will wait for all interfaces to be ready otherwise.
timeout (float) – the timeout in seconds before aborting pending controllers. Zero for infinite.
- Returns
true if the operation is successful.
- Return type
bool
- ros_controllers.stop_controllers_srv(stop_controllers, ns=None, strictness=1, start_asap=False, timeout=3.0) bool [source]
Function to start controllers on the namespace.
- Parameters
stop_controllers (list of strings) – list of controllers to stop
ns (string) – namespace
strictness (int) – strictness of the controller manager: BEST_EFFORT or STRICT (1 and 2, respectively).
start_asap (bool) – start the controllers as soon as their hardware dependencies are ready, will wait for all interfaces to be ready otherwise.
timeout (float) – the timeout in seconds before aborting pending controllers. Zero for infinite.
- Returns
true if the operation is successful.
- Return type
bool
- ros_controllers.reset_controllers_srv(reset_controllers, max_retries=10, ns=None, strictness=1, start_asap=False, timeout=3.0) bool [source]
Function to reset controllers on the namespace.
- Parameters
reset_controllers (list of strings) – list of controllers to reset
max_retries (int) – number of times to retry resetting a controller before giving up.
ns (string) – namespace
strictness (int) – strictness of the controller manager: BEST_EFFORT or STRICT (1 and 2, respectively).
start_asap (bool) – start the controllers as soon as their hardware dependencies are ready, will wait for all interfaces to be ready otherwise.
timeout (float) – the timeout in seconds before aborting pending controllers. Zero for infinite.
- Returns
true if the operation is successful.
- Return type
bool
- ros_controllers.spawn_controllers_srv(spawn_controllers, ns=None, strictness=1, start_asap=False, timeout=3.0) bool [source]
Function to spawn controllers on the namespace.
- Parameters
spawn_controllers (list of strings) – list of controllers to spawn
ns (string) – namespace
strictness (int) – strictness of the controller manager: BEST_EFFORT or STRICT (1 and 2, respectively).
start_asap (bool) – start the controllers as soon as their hardware dependencies are ready, will wait for all interfaces to be ready otherwise.
timeout (float) – the timeout in seconds before aborting pending controllers. Zero for infinite.
- Returns
true if the operation is successful.
- Return type
bool
- ros_controllers.kill_controllers_srv(kill_controllers, ns=None, strictness=1, start_asap=False, timeout=3.0) bool [source]
Function to kill controllers on the namespace.
- Parameters
kill_controllers (list of strings) – list of controllers to kill
ns (string) – namespace
strictness (int) – strictness of the controller manager: BEST_EFFORT or STRICT (1 and 2, respectively).
start_asap (bool) – start the controllers as soon as their hardware dependencies are ready, will wait for all interfaces to be ready otherwise.
timeout (float) – the timeout in seconds before aborting pending controllers. Zero for infinite.
- Returns
true if the operation is successful.
- Return type
bool