metasim.cfg.objects#

Dependency graph:

        %%{init: {"flowchart": {"defaultRenderer": "elk"}} }%%
flowchart LR
N0[BaseObjCfg]
N11[BaseRigidObjCfg]
N12[BaseArticulationObjCfg]

subgraph "Level 0"
   N0
end
subgraph "Level 1"
   N11
   N12
end
subgraph "Level 2"
   RigidObjCfg
   ArticulationObjCfg
   PrimitiveCubeCfg & PrimitiveSphereCfg & PrimitiveCylinderCfg
end
subgraph "Mixins"
   direction LR
   _FileBasedMixin
   _PrimitiveMixin
end

N0 --> N11 & N12
N11 & _FileBasedMixin ---> RigidObjCfg
N12 & _FileBasedMixin ---> ArticulationObjCfg
N11 & _PrimitiveMixin ---> PrimitiveCubeCfg & PrimitiveSphereCfg & PrimitiveCylinderCfg
    

Configuration classes for various types of objects.

Base Class

BaseObjCfg

Base class for object cfg.

Primitive Object Classes

PrimitiveCubeCfg

Primitive cube object cfg.

PrimitiveSphereCfg

Primitive sphere object cfg.

PrimitiveCylinderCfg

Primitive cylinder object cfg.

File-based Object Classes

RigidObjCfg

Rigid object cfg.

ArticulationObjCfg

Articulation object cfg.

Special Object Classes

NonConvexRigidObjCfg

Non-convex rigid object class.

Base Object#

class metasim.cfg.objects.BaseObjCfg#

Base class for object cfg.

name: str#

Object name

default_position: tuple[float, float, float]#

Default position of the object, default is (0.0, 0.0, 0.0)

default_orientation: tuple[float, float, float, float]#

Default orientation of the object, default is (1.0, 0.0, 0.0, 0.0)

Whether to fix the base link of the object, default is False

Primitive Objects#

class metasim.cfg.objects.PrimitiveCubeCfg#

Primitive cube object cfg.

name: str#

Object name

default_position: tuple[float, float, float]#

Default position of the object, default is (0.0, 0.0, 0.0)

default_orientation: tuple[float, float, float, float]#

Default orientation of the object, default is (1.0, 0.0, 0.0, 0.0)

Whether to fix the base link of the object, default is False

collision_enabled: bool#

Whether to enable collision.

physics: PhysicStateType | None#

IsaacSim’s convention for collision and gravity state. Default to None. If specified, it will be translated to collision_enabled and fix_base_link.

mass: float#

Mass of the object (in kg), default is 0.1 kg

color: list[float]#

Color of the object in RGB

size: list[float]#

Size of the object (in m).

property half_size: list[float]#

Half of the extend, for SAPIEN usage.

property volume: float#

Volume of the cube.

class metasim.cfg.objects.PrimitiveSphereCfg#

Primitive sphere object cfg.

name: str#

Object name

default_position: tuple[float, float, float]#

Default position of the object, default is (0.0, 0.0, 0.0)

default_orientation: tuple[float, float, float, float]#

Default orientation of the object, default is (1.0, 0.0, 0.0, 0.0)

Whether to fix the base link of the object, default is False

collision_enabled: bool#

Whether to enable collision.

physics: PhysicStateType | None#

IsaacSim’s convention for collision and gravity state. Default to None. If specified, it will be translated to collision_enabled and fix_base_link.

mass: float#

Mass of the object (in kg), default is 0.1 kg

color: list[float]#

Color of the object in RGB

radius: float#

Radius of the sphere (in m).

property volume: float#

Volume of the sphere.

class metasim.cfg.objects.PrimitiveCylinderCfg#

Primitive cylinder object cfg.

name: str#

Object name

default_position: tuple[float, float, float]#

Default position of the object, default is (0.0, 0.0, 0.0)

default_orientation: tuple[float, float, float, float]#

Default orientation of the object, default is (1.0, 0.0, 0.0, 0.0)

Whether to fix the base link of the object, default is False

collision_enabled: bool#

Whether to enable collision.

physics: PhysicStateType | None#

IsaacSim’s convention for collision and gravity state. Default to None. If specified, it will be translated to collision_enabled and fix_base_link.

mass: float#

Mass of the object (in kg), default is 0.1 kg

color: list[float]#

Color of the object in RGB

radius: float#

Radius of the cylinder (in m).

height: float#

Height of the cylinder (in m).

property volume: float#

Volume of the cylinder.

File-based Objects#

class metasim.cfg.objects.RigidObjCfg#

Rigid object cfg.

name: str#

Object name

default_position: tuple[float, float, float]#

Default position of the object, default is (0.0, 0.0, 0.0)

default_orientation: tuple[float, float, float, float]#

Default orientation of the object, default is (1.0, 0.0, 0.0, 0.0)

Whether to fix the base link of the object, default is False

collision_enabled: bool#

Whether to enable collision.

physics: PhysicStateType | None#

IsaacSim’s convention for collision and gravity state. Default to None. If specified, it will be translated to collision_enabled and fix_base_link.

mesh_path: str | None#

Path to the mesh file.

usd_path: str | None#

Path to the USD file.

urdf_path: str | None#

Path to the URDF file.

mjcf_path: str | None#

Path to the MJCF file.

mjx_mjcf_path: str | None#

Path to the MJCF file only used for MJX. If not specified, it will be the same as mjcf_path.

scale: float | tuple[float, float, float]#

Object scaling (in scalar) for the object, default is 1.0

class metasim.cfg.objects.ArticulationObjCfg#

Articulation object cfg.

name: str#

Object name

default_position: tuple[float, float, float]#

Default position of the object, default is (0.0, 0.0, 0.0)

default_orientation: tuple[float, float, float, float]#

Default orientation of the object, default is (1.0, 0.0, 0.0, 0.0)

Whether to fix the base link of the object, default is False

mesh_path: str | None#

Path to the mesh file.

usd_path: str | None#

Path to the USD file.

urdf_path: str | None#

Path to the URDF file.

mjcf_path: str | None#

Path to the MJCF file.

mjx_mjcf_path: str | None#

Path to the MJCF file only used for MJX. If not specified, it will be the same as mjcf_path.

scale: float | tuple[float, float, float]#

Object scaling (in scalar) for the object, default is 1.0

Special Objects#

class metasim.cfg.objects.NonConvexRigidObjCfg#

Non-convex rigid object class.

Warning

This class is deprecated and will be removed in the future.

name: str#

Object name

default_position: tuple[float, float, float]#

Default position of the object, default is (0.0, 0.0, 0.0)

default_orientation: tuple[float, float, float, float]#

Default orientation of the object, default is (1.0, 0.0, 0.0, 0.0)

Whether to fix the base link of the object, default is False

collision_enabled: bool#

Whether to enable collision.

physics: PhysicStateType | None#

IsaacSim’s convention for collision and gravity state. Default to None. If specified, it will be translated to collision_enabled and fix_base_link.

mesh_path: str | None#

Path to the mesh file.

usd_path: str | None#

Path to the USD file.

urdf_path: str | None#

Path to the URDF file.

mjcf_path: str | None#

Path to the MJCF file.

mjx_mjcf_path: str | None#

Path to the MJCF file only used for MJX. If not specified, it will be the same as mjcf_path.

scale: float | tuple[float, float, float]#

Object scaling (in scalar) for the object, default is 1.0