MultiROS API reference
Gazebo-simulation environments built on the shared UniROS proxy and utilities. Use this package when you want to train RL agents against simulated robots.
Top-level package
Gym proxy (re-export)
Re-export of the canonical multiprocessing gym proxy.
The implementation lives in uniros._proxy.GymProxy.
MultirosGym is an alias kept for backwards compatibility — both
names refer to the same class object, so isinstance(env,
MultirosGym) matches envs created through any package in the
ecosystem.
Usage:
from multiros.core import MultirosGym as gym
env = gym.make("env_name", args)
env.reset()
- multiros.core.MultirosGym
alias of
GymProxy
- class multiros.core.GymProxy(env_name, *args, **kwargs)[source]
Bases:
objectParent-side proxy for a
gym.Envrunning inside a worker process.Equivalent aliases re-exported by other packages in the ecosystem:
multiros.core.MultirosGymrealros.core.RealrosGymuniros.core.uniros_gym
All four names refer to the same class object.
Usage:
from uniros.core import uniros_gym as gym # or any alias env = gym.make("env_name", **kwargs) env.reset()
- static worker(env_name, conn, *args, **kwargs)[source]
- Parameters:
env_name (str)
conn (Connection)
args (Any)
kwargs (Any)
- Return type:
None
- property unwrapped: GymProxy
Return self as the unwrapped env.
The proxy IS the user-visible env from the parent’s perspective; whatever lives in the worker process is opaque and not accessible across the pipe (gym.Env instances typically hold non-picklable state such as _thread.RLock from rospy’s spinner threads, so sending them through the pipe raises TypeError).
Without this handler, env.unwrapped would route through __getattr__, IPC to the worker, and fail to pickle. SB3’s DummyVecEnv calls id(env.unwrapped) for uniqueness checking during construction, so this property is required for SB3 compatibility.
- classmethod make(env_name, *args, **kwargs)[source]
- step(action)[source]
- reset(seed=None, options=None)[source]
- close()[source]
- Return type:
None
The MultirosGym class in this module is an alias for
uniros._proxy.GymProxy — see the UniROS API page for the
full method reference.
Gazebo lifecycle
THE GAZEBO BRIDGE SCRIPT PROVIDES ALL THE MAIN FUNCTIONS FOR ROS TO COMMUNICATE WITH GAZEBO.
MOST OF THE ROS TOPICS & SERVICES FOR GAZEBO CAN BE FOUND HERE http://wiki.ros.org/gazebo
AND HERE https://classic.gazebosim.org/tutorials?tut=ros_comm&cat=connect_ros
- WITH THE SCRIPT HAVE THE FOLLOWING FUNCTIONALITY,
launch_gazebo: Launch Gazebo using the ROS
close_gazebo: Close a gazebo instance. This function is to close both gzclient and the gzserver
reset_gazebo: Reset the Gazebo simulation or world.
pause_gazebo: Pause the Gazebo simulation.
unpause_gazebo: Unpause the Gazebo simulation.
gazebo_step: Step gazebo simulation multiple iteration.
- multiros.utils.gazebo_core.launch_gazebo(launch_roscore=True, port=None, paused=False, use_sim_time=True, extra_gazebo_args=None, gui=False, recording=False, debug=False, physics='ode', verbose=False, output='screen', respawn_gazebo=False, pub_clock_frequency=100, server_required=False, gui_required=False, custom_world_path=None, custom_world_pkg=None, custom_world_name=None, launch_new_term=True)[source]
Launch Gazebo using the ROS. All the available options when launching gazebo with ros can be found in the /opt/ros/noetic/share/gazebo_ros/launch/empty_world.launch https://classic.gazebosim.org/tutorials?tut=ros_roslaunch&cat=connect_ros
- Parameters:
launch_roscore (bool) – if True, launch the roscore together with gazebo. Defaults to True.
port (str) – if the “launch_roscore” is “True”, it launches using the the the given port.
paused (bool) – Whether to start Gazebo in a paused state. Defaults to False.
use_sim_time (bool) – Gazebo-published simulation time, published over the ROS topic /clock (default true)
extra_gazebo_args (str) – Use this argument to add extra options to Gazebo
gui (bool) – Launch the user interface window of Gazebo (default true) (gzclient).
recording (bool) – if True, record the data from gazebo.
debug (bool) – Start gzserver (Gazebo Server) in debug mode using gdb (default false)
physics (str) – Set the physics engine (ode, dart, bullet, simbody). Currently, have support for “ode” only.
verbose (bool) – Printing errors and warnings to the terminal (default false)
output (str) – The output method for Gazebo (screen or log). Defaults to ‘screen’.
respawn_gazebo (bool) – Whether to respawn Gazebo if it is killed. Defaults to False.
pub_clock_frequency (int) – The frequency of the clock publisher (in Hz). Defaults to 100.
server_required (bool) – Terminate launch script when gzserver (Gazebo Server) exits (default false)
gui_required (bool) – Terminate launch script when gzclient (user interface window) exits (default false)
custom_world_path (str) – Absolute path to the custom world file. (optional)
custom_world_pkg (str) – if the custom_world_path is None, package of the custom world file (optional)
custom_world_name (str) – if the custom_world_pkg is not None, name of the custom world file (optional)
launch_new_term (bool) – Launch the gazebo node in a new terminal (Xterm).
- Returns:
A tuple containing the ROS port, the Gazebo port, and the process object for the launched Gazebo instance.
- Return type:
Tuple
- multiros.utils.gazebo_core.close_gazebo(process, ros_port=None, gazebo_port=None)[source]
Function to close a gazebo instance. This function is to close both gzclient and the gzserver
- Parameters:
- Returns:
True if Gazebo was closed successfully, False otherwise.
- Return type:
- multiros.utils.gazebo_core.reset_gazebo(reset_type='simulation', max_tries=5, ros_port=None, gazebo_port=None)[source]
Function to reset the Gazebo simulation or world.
- Parameters:
- Returns:
True if the service call was successful, False otherwise.
- Return type:
- multiros.utils.gazebo_core.pause_gazebo(max_tries=5, ros_port=None, gazebo_port=None)[source]
Function to pause the Gazebo simulation.
- multiros.utils.gazebo_core.unpause_gazebo(max_tries=5, ros_port=None, gazebo_port=None)[source]
Function to unpause the Gazebo simulation.
- multiros.utils.gazebo_core.gazebo_step(steps, ros_port=None, gazebo_port=None)[source]
Function to Step gazebo simulation multiple iteration.
Gazebo models
Common functions for handling models in Gazebo.
Functions provided:
gazebo_spawn_urdf— spawn a URDF model in Gazebo.spawn_model_in_gazebo— spawn a model from an SDF file in Gazebo.spawn_sdf_model_gazebo— spawn an SDF model in Gazebo (recommended).spawn_robot_in_gazebo— spawn a robot in Gazebo.gazebo_get_world_properties— get properties of the Gazebo world (spawned model names).gazebo_delete_model— delete a model from Gazebo.remove_model_gazebo— delete a model from Gazebo (recommended).gazebo_get_model_state— get the state of a model (Header, Pose, Twist).gazebo_set_model_state— set the state of a model.
- multiros.utils.gazebo_models.gazebo_spawn_urdf(model_string=None, param_name=None, model_name='robot_0', robot_namespace='/', reference_frame='world', pos_x=0.0, pos_y=0.0, pos_z=0.0, ori_x=0.0, ori_y=0.0, ori_z=0.0, ori_w=1.0, ros_port=None, gazebo_port=None)[source]
Function to spawn a URDF model in Gazebo. Spwan using either the model_string or the ros param_name.
- Parameters:
model_string (str) – A string containing the URDF data for the model to spawn. Defaults to None.
param_name (str) – The name of the parameter containing the URDF data for the model to spawn. Defaults to None.
model_name (str) – The name to assign to the spawned model. Defaults to “robot_0”.
robot_namespace (str) – The namespace to use when spawning the model. Defaults to “/”.
reference_frame (str) – The reference frame in which to spawn the model. Defaults to “world”.
pos_x (float) – The x-coordinate of the position at which to spawn the model. Defaults to 0.0.
pos_y (float) – The y-coordinate of the position at which to spawn the model. Defaults to 0.0.
pos_z (float) – The z-coordinate of the position at which to spawn the model. Defaults to 0.0.
ori_x (float) – The x-component of the quaternion representing the orientation at which to spawn the model. Defaults to 0.0.
ori_y (float) – The y-component of the quaternion representing the orientation at which to spawn the model. Defaults to 0.0.
ori_z (float) – The z-component of the quaternion representing the orientation at which to spawn the model. Defaults to 0.0.
ori_w (float) – The w-component of the quaternion representing the orientation at which to spawn the model. Defaults to 1.0.
ros_port (str) – The ROS_MASTER_URI port (optional). Defaults to None.
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional). Defaults to None.
- Returns:
- A tuple containing a boolean value indicating whether spawning was successful and
a string containing a status message.
- Return type:
- multiros.utils.gazebo_models.spawn_model_in_gazebo(model_path=None, pkg_name=None, file_name=None, model_folder='/model', model_name='model_0', robot_namespace='/', reference_frame='world', pos_x=0.0, pos_y=0.0, pos_z=0.0, ori_x=0.0, ori_y=0.0, ori_z=0.0, ori_w=1.0, ros_port=None, gazebo_port=None)[source]
Function to spawn a model from an SDF file. The user need to give either absolute model_path or pkg_name/file_name.
- Parameters:
model_path (str) – The path to the SDF file. Defaults to None.
pkg_name (str) – The name of the ROS package containing the SDF file. Defaults to None.
file_name (str) – The name of the SDF file. Defaults to None.
model_folder (str) – The folder within the ROS package containing the SDF file. Defaults to “/model”.
model_name (str) – The name to assign to the spawned model. Defaults to “model_0”.
robot_namespace (str) – The namespace to use when spawning the model. Defaults to “/”.
reference_frame (str) – The reference frame in which to spawn the model. Defaults to “world”.
pos_x (float) – The x-coordinate of the position at which to spawn the model. Defaults to 0.0.
pos_y (float) – The y-coordinate of the position at which to spawn the model. Defaults to 0.0.
pos_z (float) – The z-coordinate of the position at which to spawn the model. Defaults to 0.0.
ori_x (float) – The x-component of the quaternion representing the orientation at which to spawn the model. Defaults to 0.0.
ori_y (float) – The y-component of the quaternion representing the orientation at which to spawn the model. Defaults to 0.0.
ori_z (float) – The z-component of the quaternion representing the orientation at which to spawn the model. Defaults to 0.0.
ori_w (float) – The w-component of the quaternion representing the orientation at which to spawn the model. Defaults to 1.0.
ros_port (str) – The ROS_MASTER_URI port (optional). Defaults to None.
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional). Defaults to None.
- Returns:
True if spawning was successful, False otherwise.
- Return type:
- multiros.utils.gazebo_models.spawn_sdf_model_gazebo(model_path=None, pkg_name=None, file_name=None, model_folder='/model', model_name='model_0', namespace='/', reference_frame='world', pos_x=0.0, pos_y=0.0, pos_z=0.0, ori_x=0.0, ori_y=0.0, ori_z=0.0, ori_w=1.0, ros_port=None, gazebo_port=None, max_tries=5, pause_unpause=True)[source]
Function to spawn an SDF model in Gazebo. This function make sure that model was spawned.
- Parameters:
model_path (str) – The absolute path to the SDF file. Defaults to None.
pkg_name (str) – The name of the ROS package containing the SDF file. Defaults to None.
file_name (str) – The name of the SDF file. Defaults to None.
model_folder (str) – The folder within the ROS package containing the SDF file. Defaults to “/model”.
model_name (str) – The name to give the model when spawning it in Gazebo. Defaults to “model_0”.
namespace (str) – The namespace to use when adding the SDF to the parameter server and when launching nodes. Defaults to “/”.
reference_frame (str) – The reference frame to use when spawning the model in Gazebo. Defaults to “world”.
pos_x (float) – The x position of the model in Gazebo. Defaults to 0.0.
pos_y (float) – The y position of the model in Gazebo. Defaults to 0.0.
pos_z (float) – The z position of the model in Gazebo. Defaults to 0.0.
ori_x (float) – The x orientation of the model in Gazebo. Defaults to 0.0.
ori_y (float) – The y orientation of the model in Gazebo. Defaults to 0.0.
ori_z (float) – The z orientation of the model in Gazebo. Defaults to 0.0.
ori_w (float) – The w orientation of the model in Gazebo. Defaults to 1.0.
ros_port (str) – The ROS_MASTER_URI port (optional). Defaults to None.
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional). Defaults to None.
max_tries (int) – The maximum number of times to attempt to spawn the model. Defaults to 5.
pause_unpause (bool) – Whether to pause and unpause Gazebo before and after spawning the model. Defaults to True.
- Returns:
True if all operations were successful, False otherwise.
- Return type:
- multiros.utils.gazebo_models.spawn_robot_in_gazebo(pkg_name, model_urdf_file, model_urdf_folder='/urdf', ns='/', args_xacro=None, pub_freq=None, rob_st_term=False, gazebo_name='robot', gz_ref_frame='world', pos_x=0.0, pos_y=0.0, pos_z=0.0, ori_w=1.0, ori_x=0.0, ori_y=0.0, ori_z=0.0, controllers_file=None, controllers_list=None, ros_port=None, gazebo_port=None, controller_package_name=None)[source]
Function to spawn a robot in Gazebo.
- Parameters:
pkg_name (str) – The name of the ROS package containing the URDF/ Controllers files.
model_urdf_file (str) – The name of the URDF file.
model_urdf_folder (str) – The folder within the ROS package containing the URDF file. Defaults to “/urdf”.
ns (str) – The namespace to use when adding the URDF to the parameter server and when launching nodes. Defaults to “/”.
args_xacro (list) – Additional arguments to pass to xacro when processing the URDF file. Defaults to None.
pub_freq (float) – The maximum frequency at which the robot_state_publisher should publish the robot’s state. Defaults to None.
rob_st_term (bool) – Whether to launch the robot_state_publisher node in a new terminal window. Defaults to False.
gazebo_name (str) – The name to give the robot model when spawning it in Gazebo. Defaults to “robot”.
gz_ref_frame (str) – The reference frame to use when spawning the robot model in Gazebo. Defaults to “world”.
pos_x (float) – The x position of the robot model in Gazebo. Defaults to 0.0.
pos_y (float) – The y position of the robot model in Gazebo. Defaults to 0.0.
pos_z (float) – The z position of the robot model in Gazebo. Defaults to 0.0.
ori_w (float) – The w orientation of the robot model in Gazebo. Defaults to 1.0.
ori_x (float) – The x orientation of the robot model in Gazebo. Defaults to 0.0.
ori_y (float) – The y orientation of the robot model in Gazebo. Defaults to 0.0.
ori_z (float) – The z orientation of the robot model in Gazebo. Defaults to 0.0.
controllers_file (str) – The name of a YAML file containing controller configurations. Defaults to None.
controllers_list (list) – A list of controller names to spawn. Defaults to None.
ros_port (str) – The ROS_MASTER_URI port (optional). Defaults to None.
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional). Defaults to None.
controller_package_name (str) – The name of the package containing the controllers. Defaults to None.
- Returns:
True if all operations were successful, False otherwise.
- Return type:
- multiros.utils.gazebo_models.gazebo_get_world_properties(ros_port=None, gazebo_port=None)[source]
Function to get properties of the Gazebo world.
- Parameters:
- Returns:
- A tuple containing a boolean value indicating whether the operation was
successful, the current simulation time, and a list of model names in the world.
- Return type:
http://docs.ros.org/en/diamondback/api/gazebo/html/srv/GetWorldProperties.html
- multiros.utils.gazebo_models.gazebo_delete_model(model_name, ros_port=None, gazebo_port=None)[source]
Function to delete a model from Gazebo.
- Parameters:
- Returns:
- A tuple containing a boolean value indicating whether the operation was successful and
a string containing an error message if the operation was not successful.
- Return type:
http://docs.ros.org/en/diamondback/api/gazebo/html/srv/DeleteModel.html
- multiros.utils.gazebo_models.remove_model_gazebo(model_name, max_tries=5, ros_port=None, gazebo_port=None, pause_unpause=True)[source]
Function to make sure if a model is deleted from Gazebo.
- Parameters:
model_name (str) – The name of the model to delete.
max_tries (int) – The maximum number of times to attempt to delete the model. Defaults to 5.
ros_port (str) – The ROS_MASTER_URI port (optional). Defaults to None.
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional). Defaults to None.
pause_unpause (bool) – Whether to pause and unpause Gazebo before and after deleting the model. Defaults to True.
- Returns:
True if the operation was successful, False otherwise.
- Return type:
- multiros.utils.gazebo_models.gazebo_get_model_state(model_name, relative_entity_name='world', ros_port=None, gazebo_port=None)[source]
Function to get the state of a model in Gazebo.
- Parameters:
model_name (str) – The name of the model to get the state of.
relative_entity_name (str) – The name of the entity to which the returned pose is relative. Defaults to ‘world’
ros_port (str) – The ROS_MASTER_URI port (optional). Defaults to None.
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional). Defaults to None.
- Returns:
- A tuple containing a Header message with the timestamp of the returned state,
a Pose message with the position and orientation of the model, a Twist message with the linear and angular velocity of the model, and a boolean value indicating whether the operation was successful.
- Return type:
Tuple[Header, Pose, Twist, bool]
http://docs.ros.org/en/diamondback/api/gazebo/html/srv/GetModelState.html
- multiros.utils.gazebo_models.gazebo_set_model_state(model_name, reference_frame='world', pos_x=0.0, pos_y=0.0, pos_z=0.0, ori_x=0.0, ori_y=0.0, ori_z=0.0, ori_w=1.0, lin_vel_x=0.0, lin_vel_y=0.0, lin_vel_z=0.0, ang_vel_x=0.0, ang_vel_y=0.0, ang_vel_z=0.0, sleep_time=0.05, ros_port=None, gazebo_port=None)[source]
Function to set the state of a model in Gazebo.
- Parameters:
model_name (str) – The name of the model to set the state of.
reference_frame (str) – The name of the reference frame to use when setting the pose of the model. Defaults to “world”.
pos_x (float) – The x position of the model in Gazebo. Defaults to 0.0.
pos_y (float) – The y position of the model in Gazebo. Defaults to 0.0.
pos_z (float) – The z position of the model in Gazebo. Defaults to 0.0.
ori_x (float) – The x orientation of the model in Gazebo. Defaults to 0.0.
ori_y (float) – The y orientation of the model in Gazebo. Defaults to 0.0.
ori_z (float) – The z orientation of the model in Gazebo. Defaults to 0.0.
ori_w (float) – The w orientation of the model in Gazebo. Defaults to 1.0.
lin_vel_x (float) – The x component of the linear velocity of the model in Gazebo. Defaults to 0.0.
lin_vel_y (float) – The y component of the linear velocity of the model in Gazebo. Defaults to 0.0.
lin_vel_z (float) – The z component of the linear velocity of the model in Gazebo. Defaults to 0.0.
ang_vel_x (float) – The x component of the angular velocity of the model in Gazebo. Defaults to 0.0.
ang_vel_y (float) – The y component of the angular velocity of the model in Gazebo. Defaults to 0.0.
ang_vel_z (float) – The z component of the angular velocity of the model in Gazebo. Defaults to 0.0.
sleep_time (float) – The amount of time to sleep after setting the state of the model (optional). Defaults to 0.05 seconds.
ros_port (str) – The ROS_MASTER_URI port (optional). Defaults to None.
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional). Defaults to None.
- Returns:
True if the operation was successful, False otherwise.
- Return type:
http://docs.ros.org/en/diamondback/api/gazebo/html/srv/SetModelState.html
Gazebo physics
Common functions for handling the physics of the Gazebo simulator.
Functions provided:
get_gazebo_physics_properties— get the current physics properties.set_gazebo_physics_properties— set the physics properties.get_gazebo_max_update_rate— get the current maximum update rate.set_gazebo_max_update_rate— set the maximum update rate as a real-time factor.get_gazebo_time_step— get the current time step.set_gazebo_time_step— set the time step.get_gazebo_gravity— get the current gravity vector.set_gazebo_gravity— set the gravity vector.get_gazebo_ode_physics— get the current ODE physics properties.set_gazebo_ode_physics— set the ODE physics properties.
ROS service references:
http://docs.ros.org/en/diamondback/api/gazebo/html/srv/GetPhysicsProperties.html
http://docs.ros.org/en/diamondback/api/gazebo/html/srv/SetPhysicsProperties.html
http://docs.ros.org/en/diamondback/api/gazebo/html/msg/ODEPhysics.html
- multiros.utils.gazebo_physics.get_gazebo_physics_properties(ros_port=None, gazebo_port=None)[source]
Function to get the current physics properties of Gazebo.
- multiros.utils.gazebo_physics.set_gazebo_physics_properties(time_step=None, max_update_rate=None, gravity=None, ode_config=None, ros_port=None, gazebo_port=None)[source]
Function to set the physics properties of Gazebo.
- Parameters:
time_step (float) – The desired time step for Gazebo (optional).
max_update_rate (float) – The desired maximum update rate for Gazebo (optional).
gravity (list) – The desired gravity vector for Gazebo (optional).
ode_config (ODEPhysics) – The desired ODE physics properties for Gazebo (optional).
ros_port (str) – The ROS_MASTER_URI port (optional).
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional).
- Returns:
True if the service call was successful, False otherwise.
- Return type:
- multiros.utils.gazebo_physics.get_gazebo_max_update_rate(ros_port=None, gazebo_port=None)[source]
Function to get the current maximum update rate for Gazebo.
- multiros.utils.gazebo_physics.set_gazebo_max_update_rate(real_time_factor, ros_port=None, gazebo_port=None)[source]
Function to set the maximum update rate for Gazebo in real-time factor. 1 is real time, n is n times the rate of real time.
- multiros.utils.gazebo_physics.get_gazebo_time_step(ros_port=None, gazebo_port=None)[source]
Function to get the current time step for Gazebo.
- multiros.utils.gazebo_physics.set_gazebo_time_step(time_step, ros_port=None, gazebo_port=None)[source]
Function to set the time step for Gazebo.
- multiros.utils.gazebo_physics.get_gazebo_gravity(ros_port=None, gazebo_port=None)[source]
Function to get the current gravity vector for Gazebo.
- multiros.utils.gazebo_physics.set_gazebo_gravity(gravity, ros_port=None, gazebo_port=None)[source]
Function to set the gravity vector for Gazebo.
- multiros.utils.gazebo_physics.get_gazebo_ode_physics(ros_port=None, gazebo_port=None)[source]
Function to get the current ODE physics properties of Gazebo.
ROS helpers
ROS common
Common helpers for handling ROS from inside the multiros framework.
Functions provided:
launch_roscore— launch a roscore with a given or random (non-overlapping) port.change_ros_gazebo_master— change the current ROS and Gazebo master environment variables.get_all_the_ros_masters— get all the currently-known rosmaster ports (diagnostic).add_to_rosmaster_list— add a port to the diagnostic port log.remove_from_rosmaster_list— remove a port from the diagnostic port log.kill_all_host_ros_and_gazebo— kill ALL ROS and Gazebo processes on this host.kill_all_host_roslaunch_processes— kill ALL roslaunch processes on this host.kill_all_ros_nodes— kill every node attached to the current rosmaster.kill_ros_node— kill a single named ROS node.ros_kill_master— kill a specific rosmaster by port.clean_ros_logs— purge ROS logs.source_workspace— deprecated no-op.ros_launch_launcher— execute a roslaunch with args.ros_node_launcher— launch a ROS node from a package.ros_load_yaml— fetch and load a YAML file onto the ROS parameter server.load_urdf— load a URDF onto the parameter server.is_roscore_running— check whether a roscore is reachable.change_ros_master— set ROS_MASTER_URI for this process.change_ros_master_multi_device— set ROS_MASTER_URI for cross-machine use.change_gazebo_master— set GAZEBO_MASTER_URI for this process.init_robot_state_publisher— start the robot_state_publisher node.remove_all_from_rosmaster_list— truncate the diagnostic port log.
- multiros.utils.ros_common.register_managed_process(popen, **selectors)[source]
Register a process spawned by this script for automatic cleanup on Ctrl+C or normal interpreter exit.
Cleanup is scoped: only processes registered here are touched. Pre-existing ROS/Gazebo sessions on the host are NOT affected (unlike
kill_all_host_ros_and_gazebo).- Parameters:
popen – A
subprocess.Popen(typically the xterm wrapper shell)..terminate()will be called on cleanup.**selectors – Optional fallback identifiers used by cleanup when terminating the Popen alone is not enough (e.g. the real child detached from the wrapper). Recognised keys are
roscore_port(str | int), which triggerspkill -f "roscore -p <port>";gazebo_pids(list[int]), PIDs that will be SIGTERM’d then SIGKILL’d; andkind(str), a free-form label used in log lines.
- Return type:
None
- multiros.utils.ros_common.launch_roscore(port=None, set_new_master_vars=True)[source]
Launch a roscore on a free port and (optionally) point this process’s
ROS_MASTER_URI/GAZEBO_MASTER_URIat it.Ports are allocated via
socket.bind(('127.0.0.1', 0))so the kernel picks free ports and serializes between parallel callers on the same host — there’s no shared file to race on, and anything else squatting on a port in the historical range is naturally avoided.- Parameters:
- Returns:
(ros_port, gazebo_port)as strings.- Return type:
- multiros.utils.ros_common.change_ros_gazebo_master(ros_port, gazebo_port=None)[source]
Function to set the current ROS and Gazebo Master Environment Variables. This is for situations where we need to spawn multiple gazebo instances :website: https://wiki.ros.org/ROS/EnvironmentVariables
- multiros.utils.ros_common.get_all_the_ros_masters()[source]
Return a space-separated string of ports recorded in the diagnostic port log. Best-effort and diagnostic-only.
DEPRECATED for allocation use. Port allocation is now handled by
launch_roscoreviasocket.bind(0); this helper only reflects the best-effort log written for human debugging.- Return type:
- multiros.utils.ros_common.add_to_rosmaster_list(ros_port)[source]
DEPRECATED. Appends to the diagnostic port log only.
Port allocation is now handled by
launch_roscoredirectly viasocket.bind(0). Callers do not need to maintain a shared list.
- multiros.utils.ros_common.remove_from_rosmaster_list(ros_port)[source]
DEPRECATED. Removes
ros_portfrom the diagnostic log only.Port allocation is now handled by
launch_roscoredirectly viasocket.bind(0). Callers do not need to maintain a shared list.
- multiros.utils.ros_common.kill_all_host_ros_and_gazebo()[source]
Kill EVERY rosmaster/roslaunch/gzserver/gzclient/rosout/ robot_state_publisher/nodelet process on this host (not just the ones this script spawned).
Implemented via
killall -9so it is host-scoped: if another user or another script on the same machine is running ROS or Gazebo, this will kill their processes too. Use with care.Renamed from
kill_all_ros_and_gazeboto make the host-wide scope explicit. The old name is kept as a DeprecationWarning- emitting alias for backwards compatibility.- Returns:
- True if the kill command ran (does not verify each
process actually died).
- Return type:
- multiros.utils.ros_common.kill_all_ros_and_gazebo()[source]
DEPRECATED. Use
kill_all_host_ros_and_gazebo()instead.The old name was misleading: it sounds like it cleans up only the instances this script spawned, but it actually issues
killall -9against rosmaster/roslaunch/gzserver/etc. host-wide.- Return type:
- multiros.utils.ros_common.kill_all_host_roslaunch_processes()[source]
Kill EVERY
roslaunchprocess on this host viakillall -9.Host-scoped: not limited to this script’s rosmaster. Renamed from
kill_all_roslaunch_processto make the host-wide scope explicit. The old name is kept as a DeprecationWarning-emitting alias for backwards compatibility.- Returns:
True if the kill command ran.
- Return type:
- multiros.utils.ros_common.kill_all_roslaunch_process()[source]
DEPRECATED. Use
kill_all_host_roslaunch_processes()instead.- Return type:
- multiros.utils.ros_common.kill_all_ros_nodes(ros_port=None, gazebo_port=None)[source]
Function to kill all running ROS nodes of the specified or current Rosmaster.
- multiros.utils.ros_common.kill_ros_node(node_name, ros_port=None, gazebo_port=None)[source]
Function to kill a ROS node of the given or current Rosmaster.
- multiros.utils.ros_common.clean_ros_logs()[source]
Function to clean all the ros logs.
- Returns:
True if all the ros logs were closed.
- Return type:
- multiros.utils.ros_common.source_workspace(abs_path)[source]
DEPRECATED no-op.
This function used to launch an xterm that ran
source devel/setup.bashplusrospack profile. That approach cannot work: asourcein a child shell mutates only the child’s environment, and the child dies with the subprocess. The calling Python process’sos.environ/PYTHONPATHare unaffected, so importing packages from the workspace will not work.To use a ROS workspace from a Python process, source it in the shell that launches Python (i.e.
source devel/setup.bashin the terminal, then runpython). If you only need to refresh rospack’s cache, runrospack profiledirectly.This function is preserved for backwards compatibility but is now a no-op that emits a DeprecationWarning and a rospy logwarn. It will be removed in a future release.
- multiros.utils.ros_common.ros_launch_launcher(pkg_name=None, launch_file_name=None, launch_file_abs_path=None, args=None, launch_new_term=True, ros_port=None, gazebo_port=None)[source]
Function to execute a roslaunch with args.
- Parameters:
pkg_name (str) – Name of the package where the launch file is located.
launch_file_name (str) – Name of the launch file.
launch_file_abs_path (str) – Absolute path of the launch file
launch_new_term (bool) – Launch the process in a new terminal (Xterm).
ros_port (str) – The ROS_MASTER_URI port (optional).
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional).
- Returns:
True if the launch file was launched and False otherwise.
- Return type:
- multiros.utils.ros_common.construct_roslaunch_command(pkg_name, launch_file_name, launch_file_abs_path)[source]
Constructs a roslaunch command using either a package name and launch file name or an absolute path to a launch file.
- multiros.utils.ros_common.ros_node_launcher(pkg_name, node_name, launch_master=False, launch_new_term=True, name=None, ns='/', output='log', ros_port=None, gazebo_port=None, args=None)[source]
Function to launch a ROS node from a package. If “launch_master” is “True”, it will also launch a ROSCORE with the given “ros_port” or with a random ROS master port if “ros_port” is not specified.
- Parameters:
pkg_name (str) – Name of the package to launch the node from.
node_name (str) – Name of the node to launch.
launch_master (bool) – If ROSMASTER is not running launch it.
launch_new_term (bool) – Launch the process in a new terminal (Xterm).
name (str) – Name to give the node to be launched.
ns (str) – Namespace to give the node to be launched.
output (str) – log, screen, or None
ros_port (str) – The ROS_MASTER_URI port (optional).
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional).
args (List[str]) – List of additional arguments to pass to the rosrun command.
- Returns:
- ROS Master port, GAZEBO Master port and True if the node was launched successfully,
False otherwise.
- Return type:
- multiros.utils.ros_common.construct_rosrun_command(pkg_name, node_name, name=None, ns='/', output='log')[source]
Constructs a rosrun command using a package name and node name.
- Parameters:
- Returns:
The constructed rosrun command.
- Return type:
- multiros.utils.ros_common.ros_load_yaml(pkg_name=None, file_name=None, file_abs_path=None, ns='/', ros_port=None, gazebo_port=None)[source]
Fetch a YAML file from a package or an abs path and load it into the ROS Parameter Server.
- Parameters:
- Returns:
True if file was loaded, false otherwise.
- Return type:
- multiros.utils.ros_common.load_urdf(model_path=None, pkg_name=None, file_name=None, folder='/urdf', ns=None, args_xacro=None, param_name=None, ros_port=None, gazebo_port=None)[source]
Function to load a URDF from a ROS package to the parameter server or a string containing the processed URDF data.
- Parameters:
model_path (str) – The path to the URDF file. Defaults to None.
pkg_name (str) – The name of the ROS package containing the URDF file. Defaults to None.
file_name (str) – The name of the URDF file. Defaults to None.
folder (str) – The folder within the ROS package containing the URDF file. Defaults to “/urdf”.
ns (str) – The namespace to use when adding the URDF to the parameter server. Defaults to None.
args_xacro (list) – Additional arguments to pass to xacro when processing the URDF file. Defaults to None.
param_name (str) – The name of the parameter to use when adding the URDF to the parameter server.
ros_port (str) – The ROS_MASTER_URI port (optional). Defaults to None.
gazebo_port (str) – The GAZEBO_MASTER_URI port (optional). Defaults to None.
- Returns:
- A tuple containing a boolean value indicating whether the loading was
successful and a string containing the processed URDF data. If an error occurred while loading or processing the URDF file, the first element of the tuple will be False and the second element will be None.
- Return type:
- multiros.utils.ros_common.is_roscore_running()[source]
Function to check if a roscore is currently running.
- Returns:
True if a roscore is running, False otherwise.
- Return type:
- multiros.utils.ros_common.change_ros_master(ros_port)[source]
Function to set the current ROS Master Environment Variable.
- multiros.utils.ros_common.change_ros_master_multi_device(remote_ip, local_ip, remote_ros_port='11311')[source]
Function to set the current ROS Master Environment Variable for multi-device communication.
- multiros.utils.ros_common.change_gazebo_master(gazebo_port)[source]
Function to set the current Gazebo Master Environment Variable.
ROS controllers (re-export)
Re-export of the canonical ROS-controller helpers from
uniros.utils.ros_controllers.
Each helper wraps a controller_manager service call (load,
unload, list, switch, start, stop, reset, spawn, unspawn) with a
30-second rospy.wait_for_service timeout so a hung
controller_manager surfaces as a logged failure rather than an
indefinite hang.
Usage:
from multiros.utils.ros_controllers import load_ros_controller, ...
Re-export of uniros.utils.ros_controllers. See the UniROS
API page for the full helper reference.
ROS markers (re-export)
Re-export of the canonical ROS marker helpers from
uniros.utils.ros_markers.
Usage:
from multiros.utils.ros_markers import RosMarker, RosMarkerArray
Re-export of uniros.utils.ros_markers.
ROS kinematics (re-export)
Re-export of the canonical kinematics helpers from
uniros.utils.ros_kinematics.
Usage:
from multiros.utils.ros_kinematics import Kinematics_pyrobot, Kinematics_pykdl
Re-export of uniros.utils.ros_kinematics.
MoveIt integration
This Class is to specify all the common functions related to the handling of ROS Moveit for manipulation tasks.
- It has the following methods (Main functions),
01. set_trajectory_ee: Set a pose target for the end effector of the robot arm. 02. set_trajectory_joints: Set a joint position target for the arm joints. 03. set_gripper_joints: Set a joint position target for the gripper joints. 04. get_robot_pose: Get the current pose of the robot arm. 05. get_robot_rpy: Get the current roll, pitch, and yaw angles of the robot arm. 06. get_gripper_pose: Get the current pose of the gripper. 07. get_gripper_rpy: Get the current roll, pitch, and yaw angles of the gripper. 08. get_joint_angles_robot_arm: Get the current joint angles of the robot arm. 09. get_joint_angles_gripper: Get the current joint angles of the gripper. 10. get_joint_angles: Get the current joint angles of both the robot arm and gripper. 11. check_goal: Check if a goal position is reachable by the robot arm. 12. get_randomJointVals: Get random joint values for the robot arm. 13. get_randomPose: Get a random pose for the robot arm. 14. set_planning_time: Set the maximum time allowed for planning a trajectory. 15. set_goal_position_tolerance: Set the goal position tolerance for the robot arm. 16. set_goal_orientation_tolerance: Set the goal orientation tolerance for the robot arm. 17. set_goal_joint_tolerance: Set the goal joint tolerance for the robot arm. 18. set_max_acceleration_scaling_factor: Set the maximum acceleration scaling factor for the robot arm. 19. set_max_velocity_scaling_factor: Set the maximum velocity scaling factor for the robot arm. 20. set_trajectory_cartesian: Set a cartesian trajectory for the end effector of the robot arm. 21. stop_arm: Stop the robot arm from moving. 22. stop_gripper: Stop the gripper from moving. 23. check_goal_joint_pos: Check if a goal position is reachable by the robot arm.
- class multiros.utils.moveit_multiros.MoveitMultiros(arm_name, gripper_name=None, robot_description=None, ns=None, pause_gazebo=True)[source]
Bases:
objectA class for using MoveIt!
This class provides a set of methods for controlling a robot arm and gripper using MoveIt!. It allows you to set joint angles, execute trajectories, and check if a goal is reachable. It also provides methods for getting the current pose and joint angles of the robot arm and gripper.
To use this class, you must first initialize it with the appropriate parameters for your robot arm and gripper. You can then call the various methods provided by this class to control your robot.
- arm_execute_joint_trajectory(joint_target_values, async_move=False)[source]
Execute a joint trajectory with the robot arm.
- Parameters:
- Returns:
The result of the trajectory execution.
- Return type:
- Raises:
ValueError – If the input joint target values do not match the number of joints of the robot arm.
- gripper_execute_joint_command(target_joint_values, async_move=False)[source]
Execute a joint command with the gripper.
- Parameters:
- Returns:
The result of the command execution.
- Return type:
- Raises:
ValueError – If the input joint target values do not match the number of joints of the gripper.
- robot_pose()[source]
Get the current pose of the robot arm.
- Returns:
The current pose of the robot arm.
- Return type:
PoseStamped
- robot_rpy()[source]
Get the current roll, pitch, and yaw angles of the robot arm.
- Returns:
The current roll, pitch, and yaw angles of the robot arm.
- Return type:
List[float]
- gripper_pose(gripper_link='')[source]
Get the current pose of the gripper.
- Parameters:
gripper_link (str) – The name of the gripper link to get the pose of.
- Returns:
The current pose of the gripper.
- Return type:
PoseStamped
- joint_angles_arm()[source]
Get the current joint angles of the robot arm.
- Returns:
The current joint angles of the robot arm.
- Return type:
List[float]
- joint_angles_gripper()[source]
Get the current joint angles of the gripper.
- Returns:
The current joint angles of the gripper.
- Return type:
List[float]
- joint_angles()[source]
Get the current joint angles of both the robot arm and gripper.
- Returns:
The current joint angles of both the robot arm and gripper.
- Return type:
List[float]
- check_goal_reachable_joint_pos(joint_pos)[source]
Check if a goal position is reachable by the robot arm.
- set_trajectory_ee(position, orientation=None, async_move=False)[source]
Set a pose target for the end effector of the robot arm.
- Parameters:
- Returns:
The result of the trajectory execution.
- Return type:
- set_trajectory_joints(q_positions, async_move=False)[source]
Set a joint position target for the arm joints.
- set_gripper_joints(joint_positions, async_move=False)[source]
Set a joint position target for the gripper joints.
- get_robot_pose()[source]
Get the current pose of the robot arm.
- Returns:
The current pose of the robot arm.
- Return type:
PoseStamped
- get_robot_rpy()[source]
Get the current roll, pitch, and yaw angles of the robot arm.
- Returns:
The current roll, pitch, and yaw angles of the robot arm.
- Return type:
List[float]
- get_gripper_pose(link='')[source]
Get the current pose of the gripper.
- Parameters:
link (str) – The name of the gripper link to get the pose of.
- Returns:
The current pose of the gripper.
- Return type:
PoseStamped
- get_joint_angles_robot_arm()[source]
Get the current joint angles of the robot arm.
- Returns:
The current joint angles of the robot arm.
- Return type:
List[float]
- get_joint_angles_gripper()[source]
Get the current joint angles of the gripper.
- Returns:
The current joint angles of the gripper.
- Return type:
List[float]
- get_joint_angles()[source]
Get the current joint angles of both the robot arm and gripper.
- Returns:
The current joint angles of both the robot arm and gripper.
- Return type:
List[float]
- get_randomJointVals()[source]
Get random joint values for the robot arm.
- Returns:
Random joint values for the robot arm.
- Return type:
List[float]
- get_randomPose()[source]
Get a random pose for the robot arm.
- Returns:
A random pose for the robot arm.
- Return type:
PoseStamped
- set_planning_time(planning_time)[source]
Set the maximum allowed planning time. Specify the amount of time to be used for motion planning
- Parameters:
planning_time (float) – The maximum allowed planning time in seconds.
- Return type:
None
- set_goal_position_tolerance(position_tolerance)[source]
Set the tolerance for a target end-effector position
- Parameters:
position_tolerance (float) – The tolerance for the goal position in meters.
- Return type:
None
- set_goal_orientation_tolerance(orientation_tolerance)[source]
Set the tolerance for a target end-effector orientation.
- Parameters:
orientation_tolerance (float) – The tolerance for the goal orientation in radians.
- Return type:
None
- set_goal_joint_tolerance(joint_tolerance)[source]
Set the tolerance for a target joint configuration.
- Parameters:
joint_tolerance (float) – The tolerance for the goal joint configuration in radians.
- Return type:
None
- set_max_acceleration_scaling_factor(acceleration_scaling_factor)[source]
Set a scaling factor to reduce the maximum joint accelerations. Allowed values are in (0,1]. The default value is set in the joint_limits.yaml of the moveit_config package.
- Parameters:
acceleration_scaling_factor (float) – The maximum acceleration scaling factor.
- Return type:
None
- set_max_velocity_scaling_factor(velocity_scaling_factor)[source]
Set a scaling factor to reduce the maximum joint velocities. Allowed values are in (0,1]. The default value is set in the joint_limits.yaml of the moveit_config package.
- Parameters:
velocity_scaling_factor (float) – The maximum velocity scaling factor.
- Return type:
None
- set_trajectory_cartesian(waypoints, eef_step=0.01, jump_threshold=0.0, avoid_collisions=True)[source]
Set a cartesian trajectory for the end effector of the robot arm.
- Parameters:
waypoints (List[PoseStamped]) – The target waypoints for the end effector.
eef_step (float) – The distance between waypoints in meters (Optional).
jump_threshold (float) – The maximum distance in the configuration space between consecutive points in the resulting path (Optional).
avoid_collisions (bool) – Whether to check for collisions between waypoints or not (Optional).
- Returns:
The result of the trajectory execution.
- Return type:
Base envs
GazeboBaseEnv
- class multiros.envs.GazeboBaseEnv.GazeboBaseEnv(spawn_robot=False, urdf_pkg_name=None, urdf_file_name=None, urdf_folder='/urdf', urdf_xacro_args=None, namespace='/', robot_state_publisher_max_freq=None, new_robot_state_term=False, robot_model_name='robot', robot_ref_frame='world', robot_pos_x=0.0, robot_pos_y=0.0, robot_pos_z=0.0, robot_ori_w=1.0, robot_ori_x=0.0, robot_ori_y=0.0, robot_ori_z=0.0, controllers_file=None, controllers_list=None, reset_controllers=False, reset_mode='world', sim_step_mode=1, num_gazebo_steps=1, gazebo_max_update_rate=None, gazebo_timestep=None, kill_rosmaster=True, kill_gazebo=True, clean_logs=False, ros_port=None, gazebo_port=None, gazebo_pid=None, seed=None, unpause_pause_physics=True, action_cycle_time=0.0, log_internal_state=False, controller_package_name=None)[source]
Bases:
EnvA custom gymnasium environment for reinforcement learning using ROS and Gazebo.
Initialize the GazeboBaseEnv.
- Parameters:
spawn_robot (bool) – Whether to spawn the robot in Gazebo.
urdf_pkg_name (str) – The name of the URDF package.
urdf_file_name (str) – The name of the URDF file.
urdf_folder (str) – The folder containing the URDF file.
urdf_xacro_args (List[str]) – The arguments for the xacro processor.
namespace (str) – The ROS namespace for the robot.
robot_state_publisher_max_freq (float) – The maximum frequency for the robot state publisher.
new_robot_state_term (bool) – Whether to use a new terminal for the robot state publisher.
robot_model_name (str) – The name of the robot model in Gazebo.
robot_ref_frame (str) – The reference frame for the robot in Gazebo.
robot_pos_x (float) – The x position of the robot in Gazebo.
robot_pos_y (float) – The y position of the robot in Gazebo.
robot_pos_z (float) – The z position of the robot in Gazebo.
robot_ori_w (float) – The w orientation of the robot in Gazebo.
robot_ori_x (float) – The x orientation of the robot in Gazebo.
robot_ori_y (float) – The y orientation of the robot in Gazebo.
robot_ori_z (float) – The z orientation of the robot in Gazebo.
controllers_file (str) – The file containing the controller configurations.
controllers_list (List[str]) – The list of ROS controllers to use.
reset_controllers (bool) – Whether to reset the controllers on reset.
reset_mode (str) – The mode to use when resetting Gazebo (“world” or “simulation”).
sim_step_mode (int) – The mode to use when stepping the simulation (1 or 2).
num_gazebo_steps (int) – The number of Gazebo steps to take per step call.
gazebo_max_update_rate (float) – The maximum update rate for Gazebo.
gazebo_timestep (float) – The time step for Gazebo.
kill_rosmaster (bool) – Whether to kill the ROS master on close.
kill_gazebo (bool) – Whether to kill Gazebo on close.
clean_logs (bool) – Whether to clean the ROS logs on close.
ros_port (str) – The ROS_MASTER_URI port.
gazebo_port (str) – The GAZEBO_MASTER_URI port.
gazebo_pid (subprocess.Popen) – A subprocess.Popen object representing the running Gazebo instance
seed (int) – Seed for random number generator
unpause_pause_physics (bool) – Whether to unpause and pause Gazebo before and after each step call.
action_cycle_time (float) – The time to wait between applying actions.
log_internal_state (bool) – Whether to log the internal state of the environment.
controller_package_name (str) – The name of the package containing the controllers.
- clean_logs
Set gazebo physics parameters to change the speed of the simulation
- step(action)[source]
Take a step in the environment.
- Parameters:
action (Any) – The action to be applied to the robot.
- Returns:
The observation representing the current state of the environment. reward (float): The reward for taking the given action. terminated (bool): Whether the agent reaches the terminal state. truncated (bool): Whether the episode is truncated due to various reasons. (e.g. reaching the maximum number of steps, or end before the terminal state) info (dict): Additional information about the environment.
- Return type:
observation (Any)
GazeboGoalEnv
- class multiros.envs.GazeboGoalEnv.GazeboGoalEnv(spawn_robot=False, urdf_pkg_name=None, urdf_file_name=None, urdf_folder='/urdf', urdf_xacro_args=None, namespace='/', robot_state_publisher_max_freq=None, new_robot_state_term=False, robot_model_name='robot', robot_ref_frame='world', robot_pos_x=0.0, robot_pos_y=0.0, robot_pos_z=0.0, robot_ori_w=1.0, robot_ori_x=0.0, robot_ori_y=0.0, robot_ori_z=0.0, controllers_file=None, controllers_list=None, reset_controllers=False, reset_mode='world', sim_step_mode=1, num_gazebo_steps=1, gazebo_max_update_rate=None, gazebo_timestep=None, kill_rosmaster=True, kill_gazebo=True, clean_logs=False, ros_port=None, gazebo_port=None, gazebo_pid=None, seed=None, unpause_pause_physics=True, action_cycle_time=0.0, log_internal_state=False, controller_package_name=None)[source]
Bases:
GoalEnvA custom gymnasium robotics goal-conditioned environment for reinforcement learning using ROS and Gazebo.
Initialize the GazeboGoalEnv.
- Parameters:
spawn_robot (bool) – Whether to spawn the robot in Gazebo.
urdf_pkg_name (str) – The name of the URDF package.
urdf_file_name (str) – The name of the URDF file.
urdf_folder (str) – The folder containing the URDF file.
urdf_xacro_args (List[str]) – The arguments for the xacro processor.
namespace (str) – The ROS namespace for the robot.
robot_state_publisher_max_freq (float) – The maximum frequency for the robot state publisher.
new_robot_state_term (bool) – Whether to use a new terminal for the robot state publisher.
robot_model_name (str) – The name of the robot model in Gazebo.
robot_ref_frame (str) – The reference frame for the robot in Gazebo.
robot_pos_x (float) – The x position of the robot in Gazebo.
robot_pos_y (float) – The y position of the robot in Gazebo.
robot_pos_z (float) – The z position of the robot in Gazebo.
robot_ori_w (float) – The w orientation of the robot in Gazebo.
robot_ori_x (float) – The x orientation of the robot in Gazebo.
robot_ori_y (float) – The y orientation of the robot in Gazebo.
robot_ori_z (float) – The z orientation of the robot in Gazebo.
controllers_file (str) – The file containing the controller configurations.
controllers_list (List[str]) – The list of ROS controllers to use.
reset_controllers (bool) – Whether to reset the controllers on reset.
reset_mode (str) – The mode to use when resetting Gazebo (“world” or “simulation”).
sim_step_mode (int) – The mode to use when stepping the simulation (1 or 2).
num_gazebo_steps (int) – The number of Gazebo steps to take per step call.
gazebo_max_update_rate (float) – The maximum update rate for Gazebo.
gazebo_timestep (float) – The time step for Gazebo.
kill_rosmaster (bool) – Whether to kill the ROS master on close.
kill_gazebo (bool) – Whether to kill Gazebo on close.
clean_logs (bool) – Whether to clean the ROS logs on close.
ros_port (str) – The ROS_MASTER_URI port.
gazebo_port (str) – The GAZEBO_MASTER_URI port.
gazebo_pid (subprocess.Popen) – A subprocess.Popen object representing the running Gazebo instance
seed (int) – Seed for random number generator
unpause_pause_physics (bool) – Whether to unpause and pause Gazebo before and after each step.
action_cycle_time (float) – The time to wait between applying actions.
log_internal_state (bool) – Whether to log the internal state of the environment.
controller_package_name (str) – The name of the package containing the controllers.
- clean_logs
Set gazebo physics parameters to change the speed of the simulation
- step(action)[source]
Take a step in the environment.
- Parameters:
action (Any) – The action to be applied to the robot.
- Returns:
A dictionary containing the observation, achieved goal, and desired goal. reward (float): The reward for taking the given action. terminated (bool): Whether the agent reaches the terminal state. truncated (bool): Whether the episode is truncated due to various reasons. (e.g. reaching the maximum number of steps, or end before the terminal state) info (dict): Additional information about the environment.
- Return type:
observation (dict)
- reset(seed=None, options=None)[source]
Reset the environment.
- Parameters:
- Returns:
A dictionary containing the initial observation, achieved goal, and desired goal. info (dict): Additional information about the environment. Similar to the info returned by step().
- Return type:
observation (dict)
- compute_terminated(achieved_goal, desired_goal, info)[source]
Function to check if the episode is terminated due to reaching a terminal state.
This method should be implemented by subclasses to return a boolean value indicating whether the episode has ended (e.g., because a goal has been reached or a failure condition has been triggered).
- Parameters:
achieved_goal (Any) – The achieved goal representing the current state of the environment.
desired_goal (Any) – The desired goal representing the target state of the environment.
info (dict) – Additional information for computing the termination condition.
- Returns:
A boolean value indicating whether the episode has ended (e.g., because a goal has been reached or a failure condition has been triggered)
- compute_truncated(achieved_goal, desired_goal, info)[source]
Function to check if the episode is truncated due non-terminal reasons.
This method should be implemented by subclasses to return a boolean value indicating whether the episode has been truncated due to reasons other than reaching a terminal state. Truncated states are those that are out of the scope of the Markov Decision Process (MDP). This could include truncation due to reaching a maximum number of steps, or any other non-terminal condition that causes the episode to end early.
- Parameters:
achieved_goal (Any) – The achieved goal representing the current state of the environment.
desired_goal (Any) – The desired goal representing the target state of the environment.
info (dict) – Additional information for computing the truncation condition.
- Returns:
A boolean value indicating whether the episode has been truncated.
- compute_reward(achieved_goal, desired_goal, info)[source]
Compute the reward for achieving a given goal.
This method should be implemented by subclasses to return a scalar reward value representing how well the agent is doing in the current episode. The reward could be based on the distance to a goal, the amount of time taken to reach a goal, or any other metric that can be used to measure how well the agent is doing.
- Parameters:
achieved_goal (Any) – The achieved goal representing the current state of the environment.
desired_goal (Any) – The desired goal representing the target state of the environment.
info (dict) – Additional information for computing the reward.
- Returns:
The reward for achieving the given goal.
- Return type:
reward (float)
Wrappers
- class multiros.wrappers.normalize_action_wrapper.NormalizeActionWrapper(env)[source]
Bases:
WrapperA wrapper for normalizing the action space of an environment.
This wrapper normalizes the actions to be between -1.0 and 1.0. It can be used with environments whose action space is of type Box.
- Parameters:
env (gym.Env) – The environment to wrap.
- Raises:
ValueError – If the action space of the environment is not of type Box.
Wraps an environment to allow a modular transformation of the
step()andreset()methods.- Parameters:
env (Env) – The environment to wrap
- denormalize_action(action)[source]
Normalize the action to the range of the original action space.
- Parameters:
action (np.ndarray) – The action to normalize.
- Returns:
The normalized action.
- Return type:
np.ndarray
- reverse_action(action)[source]
Reverse the normalization of an action.
- Parameters:
action (np.ndarray) – The action to denormalize.
- Returns:
The denormalized action.
- Return type:
np.ndarray
- step(action)[source]
Take a step in the environment using a normalized action.
- Parameters:
action (np.ndarray) – The normalized action to take.
- Returns:
The observation representing the current state of the environment. reward (float): The reward for taking the given action. done (bool): Whether the episode has ended. info (dict): Additional information about the environment.
- Return type:
observation (Any)
- class multiros.wrappers.normalize_obs_wrapper.NormalizeObservationWrapper(env, normalize_goal_spaces=False)[source]
Bases:
ObservationWrapperA wrapper for normalizing the observation space of an environment.
This wrapper normalizes the observations to be between -1 and 1. It can handle environments whose observation space is either a Box or a dictionary with keys for ‘observation’, ‘achieved_goal’, and ‘desired_goal’.
- Parameters:
env (gym.Env) – The environment to wrap.
normalize_goal_spaces (bool) – Whether to normalize the achieved_goal and desired_goal spaces.
- Raises:
ValueError – If the observation space of the environment is not supported.
Constructor for the observation wrapper.
- class multiros.wrappers.time_limit_wrapper.TimeLimitWrapper(env, max_episode_steps)[source]
Bases:
Wrapper,RecordConstructorArgsThis wrapper will issue a truncated signal if a maximum number of timesteps is exceeded.
If a truncation is not defined inside the environment itself, this is the only place that the truncation signal is issued. Critically, this is different from the terminated signal that originates from the underlying environment as part of the MDP.
Initializes the
TimeLimitWrapperwith an environment and the number of steps after which truncation will occur.- Parameters:
- step(action)[source]
Steps through the environment and if the number of steps elapsed exceeds
max_episode_stepsthen truncate.