Basic Planar Robotics Environment#

class gymnasium_planar_robotics.envs.basic_envs.BasicPlanarRoboticsEnv(layout_tiles: ndarray, num_movers: int, tile_params: dict[str, any] | None = None, mover_params: dict[str, any] | None = None, initial_mover_zpos: float = 0.005, table_height: float = 0.4, std_noise: ndarray | float = 1e-05, render_mode: str | None = 'human', default_cam_config: dict[str, any] | None = None, width_no_camera_specified: int = 1240, height_no_camera_specified: int = 1080, collision_params: dict[str, any] | None = None, initial_mover_start_xy_pos: ndarray | None = None, initial_mover_goal_xy_pos: ndarray | None = None, custom_model_xml_strings: dict[str, str] | None = None, use_mj_passive_viewer: bool = False)[source]

A base class for reinforcement learning environments in the field of planar robotics that is based on MuJoCo. Note that MuJoCo does not specify basic physical units (for a more detailed explanation, see https://mujoco.readthedocs.io/en/stable/overview.html#units-are-unspecified). Thus, this environment can be used with user-specific units. However, note that the units m and kg are used for the default parameters.

Parameters:
  • layout_tiles – a numpy array of shape (num_tiles_x, num_tiles_y) indicating where to add a tile (use 1 to add a tile and 0 to leave cell empty). The x-axis and y-axis correspond to the axes of the numpy array, so the origin of the base frame is in the upper left corner.

  • num_movers – the number of movers to add

  • tile_params

    a dictionary that can be used to specify the mass and size of a tile using the keys ‘mass’ or ‘size’, defaults to None. Since one planar motor system usually only contains tiles of one type, i.e. with the same mass and size, the mass is a single float value and the size must be specified as a numpy array of shape (3,). If set to None or only one key is specified, both mass and size or the missing value are set to the following default values:

    • mass: 5.6 [kg]

    • size: [0.24/2, 0.24/2, 0.0352/2] (x,y,z) [m] (note: half-size)

  • mover_params

    a dictionary that can be used to specify the mass and size of each mover using the keys ‘mass’ or ‘size’, defaults to None. To use the same mass and size for each mover, the mass can be specified as a single float value and the size as a numpy array of shape (3,). However, the movers can also be of different types, i.e. different masses and sizes. In this case, the mass and size should be specified as numpy arrays of shapes (num_movers,) and (num_movers,3), respectively. If set to None or only one key is specified, both mass and size or the missing value are set to the following default values:

    • mass: 1.24 [kg]

    • size: [0.155/2, 0.155/2, 0.012/2] (x,y,z) [m] (note: half-size)

  • initial_mover_zpos – the initial distance between the bottom of the mover and the top of a tile, defaults to 0.005 [m]

  • table_height – the height of a table on which the tiles are placed, defaults to 0.4 [m]

  • std_noise – the standard deviation of a Gaussian with zero mean used to add noise, defaults to 1e-5. The standard deviation can be used to add noise to the mover’s position, velocity and acceleration. If you want to use different standard deviations for position, velocity and acceleration use a numpy array of shape (3,); otherwise use a single float value, meaning the same standard deviation is used for all three values.

  • render_mode – the mode that is used to render the frames (‘human’, ‘rgb_array’ or None), defaults to ‘human’. If set to None, no viewer is initialized and used, i.e. no rendering. This can be useful to speed up training.

  • default_cam_config – dictionary with attribute values of the viewer’s default camera, https://mujoco.readthedocs.io/en/latest/XMLreference.html?highlight=camera#visual-global, defaults to None

  • width_no_camera_specified – if render_mode != ‘human’ and no width is specified, this value is used, defaults to 1240

  • height_no_camera_specified – if render_mode != ‘human’ and no height is specified, this value is used, defaults to 1080

  • collision_params

    a dictionary that can be used to specify the following collision parameters, defaults to None:

    • collision shape (key: ‘shape’): can be ‘box’ or ‘circle’, defaults to ‘circle’

    • size of the collision shape (key: ‘size’), defaults to 0.11 [m]:

      • collision shape ‘circle’:

        a single float value which corresponds to the radius of the circle, or a numpy array of shape (num_movers,) to specify individual values for each mover

      • collision shape ‘box’:

        a numpy array of shape (2,) to specify x and y half-size of the box, or a numpy array of shape (num_movers, 2) to specify individual sizes for each mover

    • additional size offset (key: ‘offset’), defaults to 0.0 [m]: an additional safety offset that is added to the size of the

      collision shape. Think of this offset as increasing the size of a mover by a safety margin.

    • additional wall offset (key: ‘offset_wall’), defaults to 0.0 [m]: an additional safety offset that is added to the size

      of the collision shape to detect wall collisions. Think of this offset as moving the wall, i.e. the edge of a tile without an adjacent tile, closer to the center of the tile.

  • mover_start_xy_pos – a numpy array of shape (num_movers,2) containing the initial (x,y) starting positions of each mover. If set to None, the movers will be placed in the center of a tile, i.e. the number of tiles must be >= the number of movers; defaults to None.

  • mover_goal_xy_pos – a numpy array of shape (num_movers_with_goals,2) containing the initial (x,y) goal positions of the movers (num_movers_with_goals <= num_movers). Note that only the first 6 movers have different colors to make the movers clearly distinguishable. Movers without goals are shown in gray. If set to None, no goals will be displayed and all movers are colored in gray; defaults to None

  • custom_xml_strings

    a dictionary containing additional xml strings to provide the ability to add actuators, sensors, objects, robots, etc. to the model. The keys determine where to add a string in the xml structure and the values contain the xml string to add. The following keys are accepted:

    • ’custom_compiler_xml_str’:

      A custom ‘compiler’ xml element. Note that the entire default ‘compiler’ element is replaced.

    • ’custom_visual_xml_str’:

      A custom ‘visual’ xml element. Note that the entire default ‘visual’ element is replaced.

    • ’custom_option_xml_str’:

      A custom ‘option’ xml element. Note that the entire default ‘option’ element is replaced.

    • ’custom_assets_xml_str’:

      This xml string adds elements to the ‘asset’ grouping element.

    • ’custom_default_xml_str’:

      This xml string adds elements to the ‘default’ grouping element.

    • ’custom_worldbody_xml_str’:

      This xml string adds elements to the ‘worldbody’ grouping element.

    • ’custom_outworldbody_xml_str’:

      This xml string should be used to include files or add elements other than ‘compiler’, ‘visual’, ‘option’, ‘asset’, ‘default’ or ‘worldbody’.

    If set to None, only the basic xml string is generated, containing tiles, movers (excluding actuators), and possibly goals; defaults to None. This dictionary can be further modified using the _custom_xml_string_callback().

  • use_mj_passive_viewer – whether the MuJoCo passive_viewer should be used, defaults to False. If set to False, the Gymnasium MuJoCo WindowViewer with custom overlays is used.

check_mover_collision(mover_names: list[str], c_size: float | ndarray, add_safety_offset: bool = False, mover_qpos: ndarray | None = None, add_qpos_noise: bool = False) bool[source]

Check whether two movers specified in mover_names collide. In case of collision shape ‘box’, this method takes the orientation of the movers into account.

Parameters:
  • mover_names – a list of mover names that should be checked (correspond to the body name of the mover in the MuJoCo model)

  • c_size

    the size of the collision shape of the movers

    • collision_shape = ‘circle’:

      use a single float value to specify the same size for all movers and a numpy array of shape (num_movers,) to specify individual sizes for each mover

    • collision_shape = ‘box’:

      use a numpy array of shape (2,) to specify the same size for all movers and a numpy array of shape (num_movers,2) to specify individual sizes for each mover

  • add_safety_offset – whether to add the size offset (can be specified using: collision_params[“offset”]), defaults to False. Note that the same size offset is added for both movers.

  • mover_qpos – the qpos of the movers specified as a numpy array of shape (num_movers,7) (x_p,y_p,z_p,w_o,x_o,y_o,z_o). If set to None, the current qpos of the movers in the MuJoCo model is used; defaults to None

  • add_qpos_noise – whether to add Gaussian noise to the qpos of the movers, defaults to False. Only used if mover_qpos is not None.

Returns:

True if the movers collide, False otherwise

check_wall_collision(mover_names: list[str], c_size: float | ndarray, add_safety_offset: bool = False, mover_qpos: ndarray | None = None, add_qpos_noise: bool = False) ndarray[source]

Check whether the qpos of the movers listed in mover_names are valid, i.e. no wall collisions.

Parameters:
  • mover_names – a list of mover names that should be checked (correspond to the body name of the mover in the MuJoCo model)

  • c_size

    the size of the collision shape

    • collision_shape = ‘circle’:

      use a single float value to specify the same size for all movers and a numpy array of shape (num_movers,) to specify individual sizes for each mover

    • collision_shape = ‘box’:

      use a numpy array of shape (2,) to specify the same size for all movers and a numpy array of shape (num_movers,2) to specify individual sizes for each mover

  • add_safety_offset – whether to add the size offset (can be specified using: collision_params[“offset”]), defaults to False. Note that the same size offset is added for all movers.

  • mover_qpos – a numpy array of shape (num_qpos,7) containing the qpos (x_p,y_p,z_p,w_o,x_o,y_o,z_o) of each mover or None. If set to None, the current qpos of each mover in the MuJoCo model is used; defaults to None

  • add_qpos_noise – whether to add Gaussian noise to the qpos of the movers, defaults to False. Only used if mover_qpos is not None.

Returns:

a numpy array of shape (num_movers,), where an element is 1 if the qpos is valid (no wall collision), otherwise 0

close() None[source]

Close the environment.

generate_model_xml_string(mover_start_xy_pos: ndarray | None = None, mover_goal_xy_pos: ndarray | None = None, custom_xml_strings: dict[str, str] = None) str[source]

Generate a MuJoCo model xml string based on the mover-tile configuration of the environment.

Parameters:
  • mover_start_xy_pos – a numpy array of shape (num_movers,2) containing the (x,y) starting positions of each mover. If set to None, the movers will be placed in the center of a tile, i.e. the number of tiles must be >= the number of movers; defaults to None.

  • mover_goal_xy_pos – a numpy array of shape (num_movers_with_goals,2) containing the (x,y) goal positions of the movers (num_movers_with_goals <= num_movers). Note that only the first 6 movers have different colors to make the movers clearly distinguishable. Movers without goals are shown in gray. If set to None, no goals will be displayed and all movers are colored in gray; defaults to None

  • custom_xml_strings

    a dictionary containing additional xml strings to provide the ability to add actuators, sensors, objects, robots, etc. to the model. The keys determine where to add a string in the xml structure and the values contain the xml string to add. The following keys are accepted:

    • ’custom_compiler_xml_str’:

      A custom ‘compiler’ xml element. Note that the entire default ‘compiler’ element is replaced.

    • ’custom_visual_xml_str’:

      A custom ‘visual’ xml element. Note that the entire default ‘visual’ element is replaced.

    • ’custom_option_xml_str’:

      A custom ‘option’ xml element. Note that the entire default ‘option’ element is replaced.

    • ’custom_assets_xml_str’:

      This xml string adds elements to the ‘asset’ grouping element.

    • ’custom_default_xml_str’:

      This xml string adds elements to the ‘default’ grouping element.

    • ’custom_worldbody_xml_str’:

      This xml string adds elements to the ‘worldbody’ grouping element.

    • ’custom_outworldbody_xml_str’:

      This xml string should be used to include files or add elements other than ‘compiler’, ‘visual’, ‘option’, ‘asset’, ‘default’ or ‘worldbody’.

    If set to None, only the basic xml string is generated, containing tiles, movers (excluding actuators), and possibly goals; defaults to None

Returns:

MuJoCo model xml string

get_c_size_arr(c_size: float | ndarray, num_reps: int) ndarray[source]

Return the size of the collision shape as a numpy array of shape (num_reps,1) or (num_reps,2) depending on the collision shape. This method should be used to obtain the appropriate c_size_arr if the same size is to be used for all movers.

Parameters:
  • c_size

    the size of the collision shape:

    • collision_shape = ‘circle’:

      use a single float value to specify the same size for all movers and a numpy array of shape (num_reps,) to specify individual sizes for each mover

    • collision_shape = ‘box’:

      use a numpy array of shape (2,) to specify the same size for all movers and a numpy array of shape (num_reps,2) to specify individual sizes for each mover

  • num_reps – the number of repetitions of c_size if the same size of collision shape is to be used for all movers. Otherwise, this value is ignored.

Returns:

the collision shape sizes as a numpy array of a suitable shape:

  • collision_shape = ‘circle’:

    a numpy array of shape (num_reps,1)

  • collision_shape = ‘box’:

    a numpy array of shape (num_reps,2) if c_size is a numpy array of shape (2,). Otherwise, c_size is not modified.

get_mover_qacc(mover_name: str, add_noise: bool = False) ndarray[source]

Returns the linear and angular acceleration (qacc) of the desired mover.

Parameters:
  • mover_name – name of the mover for which the acceleration should be returned (corresponds to the body name of the mover in the MuJoCo model)

  • add_noise – whether to add Gaussian noise, defaults to False

Returns:

linear and angular acceleration of the mover (x,y,z,a,b,c)

get_mover_qacc_arr(mover_names: list[str], add_noise: bool = False) ndarray[source]

Return the qacc of several movers as a numpy array of shape (num_movers,6).

Parameters:
  • mover_names – a list of mover names for which the qacc should be returned (correspond to the body name of the mover in the MuJoCo model)

  • add_noise – whether to add Gaussian noise to the qacc of the movers, defaults to False

Returns:

a numpy array of shape (num_movers,6) containing the qacc (x,y,z,a,b,c) of each mover. The order of the qacc corresponds to the order of the mover names.

get_mover_qpos(mover_name: str, add_noise: bool = False) ndarray[source]

Returns the position and orientation of the desired mover. The orientation is returned as a quaternion (w,x,y,z). Note that the z-pos is the distance between the bottom of the mover and the top of a tile. In contrast, the z-pos in the MuJoCo model is the previously mentioned distance + half the height of a mover.

Parameters:
  • mover_name – name of the mover for which the position and orientation should be returned (corresponds to the body name of the mover in the MuJoCo model)

  • add_noise – whether to add Gaussian noise, defaults to False

Returns:

position and orientation of the desired mover (x_p,y_p,z_p,w_o,x_o,y_o,z_o)

get_mover_qpos_arr(mover_names: list[str], add_noise: bool = False) ndarray[source]

Return the qpos of several movers as a numpy array of shape (num_movers,7).

Parameters:
  • mover_names – a list of mover names for which the qpos should be returned (correspond to the body name of the mover in the MuJoCo model)

  • add_noise – whether to add Gaussian noise to the qpos of the movers, defaults to False

Returns:

a numpy array of shape (num_movers,7) containing the qpos (x_p,y_p,z_p,w_o,x_o,y_o,z_o) of each mover. The order of the qpos corresponds to the order of the mover names.

get_mover_qvel(mover_name: str, add_noise: bool = False) ndarray[source]

Return the linear and angular velocities (qvel) of the desired mover.

Parameters:
  • mover_name – name of the mover for which the velocity should be returned (corresponds to the body name of the mover in the MuJoCo model)

  • add_noise – whether to add Gaussian noise, defaults to False

Returns:

linear and angular velocities of the mover (x,y,z,a,b,c)

get_mover_qvel_arr(mover_names: list[str], add_noise: bool = False) ndarray[source]

Return the qvel of several movers as a numpy array of shape (num_movers,6).

Parameters:
  • mover_names – a list of mover names for which the qvel should be returned (correspond to the body name of the mover in the MuJoCo model)

  • add_noise – whether to add Gaussian noise to the qvel of the movers, defaults to False

Returns:

a numpy array of shape (num_movers,6) containing the qvel (x,y,z,a,b,c) of each mover. The order of the qvel corresponds to the order of the mover names.

get_tile_indices_mask(mask: ndarray) tuple[ndarray, ndarray][source]

Find the x and y indices of tiles that correspond to the specified structure (the mask) in the tile layout. Note that the indices of the top left tile in the mask are returned.

Parameters:

mask – a 2D numpy array containing only 0 and 1 which specifies the structure to be found in the tile layout

Returns:

the x and y indices of the tiles in separate numpy arrays, each of shape (num_mask_found,)

get_tile_xy_pos() tuple[ndarray, ndarray][source]

Find the (x,y)-positions of the tiles. The position of a tile in the tile layout with index (i_x,i_y), can be found using (x-pos[i_x,i_y], y-pos[i_x,i_y]), where x-pos and y-pos are returned by this method. Note that the base frame is in the upper left corner.

Returns:

the x and y positions of the tiles in separate numpy arrays, each of shape (num_tiles_x, num_tiles_y)

qpos_is_valid(qpos: ndarray, c_size: float | ndarray, add_safety_offset: bool = False) ndarray[source]

Check whether qpos is valid. This method considers the edges as imaginary walls if there is no other tile next to that edge. A position is valid if it is above a tile and the distance to the walls is greater that the required safety margin, i.e. no collision with a wall. This also ensures that the position is reachable in case the specified position is a goal position.

This method allows to check multiple qpos at the same time, where the movers can be of different sizes. The orientation of the mover is taken into account if collision_shape = ‘box’, otherwise (collision_shape = ‘circle’) the orientation of the mover is ignored.

Parameters:
  • qpos – a numpy array of shape (num_qpos,7) containing the qpos (x_p,y_p,z_p,w_o,x_o,y_o,z_o) to be checked

  • c_size

    the size of the collision shape

    • collision_shape = ‘circle’:

      use a single float value to specify the same size for all movers and a numpy array of shape (num_qpos,) to specify individual sizes for each mover

    • collision_shape = ‘box’:

      use a numpy array of shape (2,) to specify the same size for all movers and a numpy array of shape (num_qpos,2) to specify individual sizes for each mover

  • add_safety_offset – whether to add the size offset (can be specified using: collision_params[“offset”]), defaults to False. Note that the same size offset is added for all movers.

Returns:

a numpy array of shape (num_qpos,), where an element is 1 if the qpos is valid, otherwise 0

render() ndarray | None[source]

Compute frames depending on the initially specified render_mode. Before the corresponding viewer is updated, the _render_callback() is called to give the opportunity to add more functionality.

Returns:

returns a numpy array if render_mode != ‘human’, otherwise it returns None (render_mode ‘human’)

window_viewer_is_running() bool[source]

Check whether the window viewer (render_mode ‘human’) is active, i.e. the window is open.

Returns:

True if the window is open, False otherwise