ros_gazebo_gym.core
Contains the core functions and classes that are used to setup the ros_gazebo_gym gymnasium environments. This contains functions for download the required dependencies, starting ROS launch files, connecting to the gazebo simulation and controllers, etc.
Submodules
Package Contents
Classes
Class that contains several methods that can be used to interact with the |
|
Class that contains several methods that can be used to interact with the Gazebo |
|
A class for importing modules lazily. |
|
Class used to launch ROS launch files. |
- class ros_gazebo_gym.core.ControllersConnection(namespace='', controllers_list=None)[source]
Class that contains several methods that can be used to interact with the ros_control controllers.
- list_service
The controller list service.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- switch_service
The controller switch service.
- Type:
rospy.impl.tcpros_service.ServiceProxy
Initialize the ControllersConnection instance.
- Parameters:
- property controllers_list
Returns the list of available controllers.
- property gazebo
Returns whether a ROS Gazebo simulation is running.
- property gazebo_paused
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:
- 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.
- class ros_gazebo_gym.core.GazeboConnection(reset_world_or_sim='WORLD', max_retry=20, retry_rate=5, log_reset=True)[source]
Class that contains several methods that can be used to interact with the Gazebo simulation.
- pause_proxy
ROS service that pauses the gazebo simulator.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- unpause_proxy
ROS service that un-pauses the gazebo simulator.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- reset_simulation_proxy
ROS service that resets the gazebo simulator.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- reset_world_proxy
ROS service that resets the gazebo world.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- spawn_sdf_proxy
ROS service that spawns a sdf model.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- spawn_urdf_proxy
ROS service that spawns a urdf model.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- get_model_state_proxy
ROS service used to set get model states.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- set_model_state_proxy
ROS service used to set the model state of a object.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- set_link_state_proxy
ROS service used to set the link states.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- get_link_state_proxy
ROS service used to get the link states.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- set_model_configuration_proxy
ROS service that sets the configuration of a model.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- get_physics_proxy
ROS service used to retrieve the physics properties.
- Type:
rospy.impl.tcpros_service.ServiceProxy
- set_physics_proxy
ROS service used to set the physics properties.
- Type:
rospy.impl.tcpros_service.ServiceProxy
Initiate the GazeboConnection instance.
- Parameters:
reset_world_or_sim (str, optional) – Whether you want to reset the whole simulation “SIMULATION” at startup or only the world “WORLD” (object positions). Defaults to “WORLD”.
max_retry (int, optional) – How many times a command to the simulator is retried before giving up. Defaults to
30
.retry_rate (int, optional) – The rate at which the retry is done. Defaults to
2
(i.e. 0.5 seconds).log_reset (bool, optional) – Whether we want to print a log statement when the world/simulation is reset. Defaults to
True
.
- property physics_properties
Retrieves the physics properties from gazebo.
- property time
Retrieves the Gazebo time.
- reset_sim()[source]
Reset the simulation or the world.
Note
Implemented like this since in some simulations, when reset the simulation the systems that work with TF break. In this case we ONLY resets the object position, not the entire simulation.
- get_model_state(model_name)[source]
Retrieve the current state of a model.
- Parameters:
model_name (str) – The name of the model for which you want to retrieve the state.
- Returns:
The pose of the model.
- Return type:
- Raises:
ros_gazebo_gym.exceptions.GetModelStateError – Thrown when the model state retrieval failed.
- set_model_state(model_state)[source]
Sets the state of a model.
- Parameters:
model_state (
gazebo_msgs.msg.SetModelState
) – The model_state object.- Returns:
Boolean specifying whether the model state was set successfully.
- Return type:
- Raises:
ros_gazebo_gym.exceptions.SetModelStateError – Thrown when the model state could not be set.
- get_link_state(link_name)[source]
Retrieve the current state of a model.
- Parameters:
link_name (str) – The name of the robot link.
- Returns:
The pose of the robot link.
- Return type:
- Raises:
GetLinkStateError – Thrown when the link state retrieval failed.
- set_model_configuration(model_name, joint_names, joint_positions, pause=True)[source]
Sets the configuration of a model.
- Parameters:
- Returns:
- Boolean specifying whether the model configuration was set
successfully.
- Return type:
- Raises:
ros_gazebo_gym.exceptions.SetModelConfigurationError – Thrown when the model configuration could not be set.
- get_physics_properties()[source]
Retrieve physics properties from gazebo.
- Returns:
- Physics properties
message.
- Return type:
gazebo_msgs.srv.GetPhysicsPropertiesResponse
- Raises:
ros_gazebo_gym.errors.GetPhysicsPropertiesError – Thrown when something goes wrong while trying to retrieve the physics properties.
- set_physics_properties(**kwargs)[source]
Change physics properties of the gazebo physics engine. These properties have to be supplied as a keyword argument.
Tip
You can use the
GazeboConnection.set_physics_proxy
If you want to send agazebo_msgs.srv.SetPhysicsProperties
message directly.- Parameters:
**kwargs – Keyword arguments specifying the physics properties you want to set.
- Raises:
SetPhysicsPropertiesError – Thrown when something goes wrong while setting the physics properties.
- spawn_object(object_name, model_name, models_folder_path, pose=None)[source]
Spawns a object from the model directory into gazebo.
- Parameters:
object_name (str) – The name you want the model to have.
model_name (str) – The model type (The name of the xml file you want to use).
models_folder_path (str) – The folder in which you want to search for the models.
pose (
geometry_msgs.msg.Pose
, optional) – The pose of the model, by defaultgeometry_msgs.msg.Pose
.
- Returns:
A boolean specifying whether the model was successfully spawned.
- Return type:
- Raises:
ros_gazebo_gym.exceptions.SpawnModelError – When model was not spawned successfully.
- class ros_gazebo_gym.core.LazyImporter(module_name)[source]
A class for importing modules lazily.
This class can be used to import modules and module objects lazily. It caches imported modules and module objects to avoid repeated imports.
Initialize a new LazyImporter object.
- Parameters:
module_name (str) – The name of the module to import.
- class ros_gazebo_gym.core.ROSLauncher[source]
Bases:
object
Class used to launch ROS launch files.
- successful
Whether the launch file was successfully launched. This only specifies if the launchfile was successfully executed not if it encountered errors.
- Type:
- launched
- classmethod terminate(process_name)[source]
Terminate a launched process.
- Parameters:
process_name (str) – The process name.
- classmethod launch(package_name, launch_file_name, workspace_path=None, log_file=None, critical=False, wait_time=2, outdated_warning=False, **kwargs)[source]
Launch a given launchfile while also installing the launchfile package and or dependencies. This is done by using the ros_gazebo_gym dependency index.
- Parameters:
package_name (str) – The package that contains the launchfile.
launch_file_name (str) – The launchfile name.
workspace_path (str, optional) – The path of the catkin workspace. Defaults to
None
meaning the path will be determined.log_file (str, optional) – The log file to write the
stdout
to. Defaults toNone
meaning thestdout
will be written to console.critical (bool, optional) – Whether the process is critical and an error message should be shown when the process is no longer running.
wait_time (int, optional) – The time to wait before checking if the was launched successfully and is still running. Defaults to
2
.outdated_warning (bool, optional) – Whether to show a update warning when the package is outdated. Defaults to
False
.**kwargs – Keyword arguments you want to pass to the launchfile.
- Raises:
Exception – When something went wrong when launching the launchfile.