ros_gazebo_gym.core.controllers_connection

Contains a python utility class that makes it easier to interact with ros_control controllers.

Module Contents

Classes

ControllersConnection

Class that contains several methods that can be used to interact with the

Attributes

CONNECTION_TIMEOUT

ros_gazebo_gym.core.controllers_connection.CONNECTION_TIMEOUT = 10[source]
class ros_gazebo_gym.core.controllers_connection.ControllersConnection(namespace='', controllers_list=None)[source]

Class that contains several methods that can be used to interact with the ros_control controllers.

list_service_name

The name of the controller list service.

Type:

str

list_service

The controller list service.

Type:

rospy.impl.tcpros_service.ServiceProxy

switch_service_name

The name of the controller switch service.

Type:

str

switch_service

The controller switch service.

Type:

rospy.impl.tcpros_service.ServiceProxy

Initialize the ControllersConnection instance.

Parameters:
  • namespace (str, optional) – The namespace on which the robot controllers can be found. Defaults to "".

  • controllers_list (list, optional) – A list with currently available controllers to look for. Defaults to None, which means that the class will try to retrieve all the running controllers.

property controllers_list[source]

Returns the list of available controllers.

property gazebo[source]

Returns whether a ROS Gazebo simulation is running.

property gazebo_paused[source]

Returns whether the Gazebo simulation is paused.

switch_controllers(controllers_on, controllers_off, strictness=1, timeout=0.0)[source]

Function used to switch controllers on and off.

Parameters:
  • controllers_on (list) – The controllers you want to turn on.

  • controllers_off (list) – The controllers you want to turn off.

  • strictness (int, optional) – Whether the switching will fail if anything goes wrong. Defaults to 1.

  • timeout (float) – The timeout before the request is cancelled. Defaults to 0.0 meaning no timeout.

Returns:

Boolean specifying whether the switch was successful.

Return type:

bool

reset_controllers(timeout=1.0)[source]

Resets the currently running controllers by turning them off and on.

Parameters:

timeout (float) – The timeout before the request is cancelled. Defaults to 0.0 meaning no timeout.

pause_controllers(controller_list=None, filter_list=[])[source]

Pauses controllers.

Parameters:
  • controller_list (list, optional) – The controllers you want to pause. Defaults to None, which means that the class will pause all the running controllers.

  • filter_list (list, optional) – The controllers you want to ignore when pausing. Defaults to [].

unpause_controllers()[source]

Unpauses all the paused controllers.

Returns:

Boolean specifying whether the unpause was successful.

Return type:

bool