robosuite.models.objects package
Subpackages
Submodules
robosuite.models.objects.generated_objects module
- class robosuite.models.objects.generated_objects.CompositeBodyObject(name, objects, object_locations, object_quats=None, object_parents=None, joints='default', body_joints=None, sites=None)
Bases:
robosuite.models.objects.objects.MujocoGeneratedObject
An object constructed out of multiple bodies to make more complex shapes.
- Parameters
name (str) – Name of overall object
objects (MujocoObject or list of MujocoObjects) – object(s) to combine to form the composite body object. Note that these objects will be added sequentially, so if an object is required to be nested relative to another object, that nested object should be listed after the parent object. Note that all top-level joints for any inputted objects are automatically stripped
object_locations (list) – list of body locations in the composite. Each location should be a list or tuple of 3 elements and all locations are taken relative to that object’s parent body. Giving None for a location results in (0,0,0) for that object.
object_quats (None or list) – list of (w, x, y, z) quaternions for each body. None results in (1,0,0,0) for that object.
object_parents (None or list) – Parent bodies to append each object to. Note that specifying “None” will automatically append all objects to the root body (“root”)
joints (None or list) – Joints to use for the top-level composite body object. If None, no joints will be used for this top-level object. If “default”, a single free joint will be added to the top-level body of this object. Otherwise, should be a list of dictionaries, where each dictionary should specify the specific joint attributes necessary. See http://www.mujoco.org/book/XMLreference.html#joint for reference.
body_joints (None or dict) – If specified, maps body names to joint specifications to append to that body. If None, no extra joints will be used. If mapped value is “default”, a single free joint will be added to the specified body. Otherwise, should be a list of dictionaries, where each dictionary should specify the specific joint attributes necessary. See http://www.mujoco.org/book/XMLreference.html#joint for reference.
sites (None or list) – list of sites to add to top-level composite body object. If None, only the default top-level object site will be used. Otherwise, should be a list of dictionaries, where each dictionary should specify the appropriate attributes for the given site. See http://www.mujoco.org/book/XMLreference.html#site for reference.
- property bottom_offset
Returns vector from model root body to model bottom. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
- property horizontal_radius
Returns maximum distance from model root body to any radial point of the model.
Helps us put models programmatically without them flying away due to a huge initial contact force. Must be defined by subclass.
- Returns
radius
- Return type
float
- property top_offset
Returns vector from model root body to model top. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
- class robosuite.models.objects.generated_objects.CompositeObject(name, total_size, geom_types, geom_sizes, geom_locations, geom_quats=None, geom_names=None, geom_rgbas=None, geom_materials=None, geom_frictions=None, rgba=None, density=100.0, solref=(0.02, 1.0), solimp=(0.9, 0.95, 0.001), locations_relative_to_center=False, joints='default', sites=None, obj_types='all', duplicate_collision_geoms=True)
Bases:
robosuite.models.objects.objects.MujocoGeneratedObject
An object constructed out of basic geoms to make more intricate shapes.
Note that by default, specifying None for a specific geom element will usually set a value to the mujoco defaults.
- Parameters
name (str) – Name of overall object
total_size (list) – (x, y, z) half-size in each dimension for the bounding box for this Composite object
geom_types (list) – list of geom types in the composite. Must correspond to MuJoCo geom primitives, such as “box” or “capsule”.
geom_locations (list) – list of geom locations in the composite. Each location should be a list or tuple of 3 elements and all locations are relative to the lower left corner of the total box (e.g. (0, 0, 0) corresponds to this corner).
geom_sizes (list) – list of geom sizes ordered the same as @geom_locations
geom_quats (None or list) – list of (w, x, y, z) quaternions for each geom.
geom_names (None or list) – list of geom names ordered the same as @geom_locations. The names will get appended with an underscore to the passed name in @get_collision and @get_visual
geom_rgbas (None or list) – list of geom colors ordered the same as @geom_locations. If passed as an argument, @rgba is ignored.
geom_materials (None or list of CustomTexture) – list of custom textures to use for this object material
geom_frictions (None or list) – list of geom frictions to use for each geom.
rgba (None or list) – (r, g, b, a) default values to use if geom-specific @geom_rgbas isn’t specified for a given element
density (float or list of float) – either single value to use for all geom densities or geom-specific values
solref (list or list of list) – parameters used for the mujoco contact solver. Can be single set of values or element-specific values. See http://www.mujoco.org/book/modeling.html#CSolver for details.
solimp (list or list of list) – parameters used for the mujoco contact solver. Can be single set of values or element-specific values. See http://www.mujoco.org/book/modeling.html#CSolver for details.
locations_relative_to_center (bool) – If true, @geom_locations will be considered relative to the center of the overall object bounding box defined by @total_size. Else, the corner of this bounding box is considered the origin.
joints (None or list) – Joints to use for this composite object. If None, no joints will be used for this top-level object. If “default”, a single free joint will be added to this object. Otherwise, should be a list of dictionaries, where each dictionary should specify the specific joint attributes necessary. See http://www.mujoco.org/book/XMLreference.html#joint for reference.
sites (None or list) –
- list of sites to add to this composite object. If None, only the default
object site will be used. Otherwise, should be a list of dictionaries, where each dictionary
should specify the appropriate attributes for the given site. See http://www.mujoco.org/book/XMLreference.html#site for reference.
obj_types (str or list of str) – either single obj_type for all geoms or geom-specific type. Choices are {“collision”, “visual”, “all”}
- property bottom_offset
Returns vector from model root body to model bottom. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
- get_bounding_box_size()
- property horizontal_radius
Returns maximum distance from model root body to any radial point of the model.
Helps us put models programmatically without them flying away due to a huge initial contact force. Must be defined by subclass.
- Returns
radius
- Return type
float
- in_box(position, object_position)
Checks whether the object is contained within this CompositeObject. Useful for when the CompositeObject has holes and the object should be within one of the holes. Makes an approximation by treating the object as a point, and the CompositeBoxObject as an axis-aligned grid. :param position: 3D body position of CompositeObject :param object_position: 3D position of object to test for insertion
- property top_offset
Returns vector from model root body to model top. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
- class robosuite.models.objects.generated_objects.PrimitiveObject(name, size=None, rgba=None, density=None, friction=None, solref=None, solimp=None, material=None, joints='default', obj_type='all', duplicate_collision_geoms=True)
Bases:
robosuite.models.objects.objects.MujocoGeneratedObject
Base class for all programmatically generated mujoco object i.e., every MujocoObject that does not have an corresponding xml file
- Parameters
name (str) – (unique) name to identify this generated object
size (n-tuple of float) – relevant size parameters for the object, should be of size 1 - 3
rgba (4-tuple of float) – Color
density (float) – Density
friction (3-tuple of float) – (sliding friction, torsional friction, and rolling friction). A single float can also be specified, in order to set the sliding friction (the other values) will be set to the MuJoCo default. See http://www.mujoco.org/book/modeling.html#geom for details.
solref (2-tuple of float) – MuJoCo solver parameters that handle contact. See http://www.mujoco.org/book/XMLreference.html for more details.
solimp (3-tuple of float) – MuJoCo solver parameters that handle contact. See http://www.mujoco.org/book/XMLreference.html for more details.
material (CustomMaterial or ‘default’ or None) –
if “default”, add a template material and texture for this object that is used to color the geom(s). Otherwise, input is expected to be a CustomMaterial object
See http://www.mujoco.org/book/XMLreference.html#asset for specific details on attributes expected for Mujoco texture / material tags, respectively
Note that specifying a custom texture in this way automatically overrides any rgba values set
joints (None or str or list of dict) – Joints for this object. If None, no joint will be created. If “default”, a single (free) joint will be crated. Else, should be a list of dict, where each dictionary corresponds to a joint that will be created for this object. The dictionary should specify the joint attributes (type, pos, etc.) according to the MuJoCo xml specification.
obj_type (str) –
Geom elements to generate / extract for this object. Must be one of:
- ’collision’
Only collision geoms are returned (this corresponds to group 0 geoms)
- ’visual’
Only visual geoms are returned (this corresponds to group 1 geoms)
- ’all’
All geoms are returned
duplicate_collision_geoms (bool) – If set, will guarantee that each collision geom has a visual geom copy
- bottom_offset()
Returns vector from model root body to model bottom. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
- horizontal_radius()
Returns maximum distance from model root body to any radial point of the model.
Helps us put models programmatically without them flying away due to a huge initial contact force. Must be defined by subclass.
- Returns
radius
- Return type
float
- top_offset()
Returns vector from model root body to model top. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
robosuite.models.objects.objects module
- class robosuite.models.objects.objects.MujocoGeneratedObject(obj_type='all', duplicate_collision_geoms=True)
Bases:
robosuite.models.objects.objects.MujocoObject
Base class for all procedurally generated objects.
- Parameters
obj_type (str) –
Geom elements to generate / extract for this object. Must be one of:
- ’collision’
Only collision geoms are returned (this corresponds to group 0 geoms)
- ’visual’
Only visual geoms are returned (this corresponds to group 1 geoms)
- ’all’
All geoms are returned
duplicate_collision_geoms (bool) – If set, will guarantee that each collision geom has a visual geom copy
- append_material(material)
Adds a new texture / material combination to the assets subtree of this XML Input is expected to be a CustomMaterial object
See http://www.mujoco.org/book/XMLreference.html#asset for specific details on attributes expected for Mujoco texture / material tags, respectively
Note that the “file” attribute for the “texture” tag should be specified relative to the textures directory located in robosuite/models/assets/textures/
- Parameters
material (CustomMaterial) – Material to add to this object
- bottom_offset()
Returns vector from model root body to model bottom. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
- exclude_from_prefixing(inp)
Exclude all shared materials and their associated names from being prefixed.
- Parameters
inp (ET.Element or str) – Element or its attribute to check for prefixing.
- Returns
True if we should exclude the associated name(s) with @inp from being prefixed with naming_prefix
- Return type
bool
- static get_collision_attrib_template()
Generates template with collision attributes for a given geom
- Returns
Initial template with ‘pos’ and ‘group’ already specified
- Return type
dict
- static get_visual_attrib_template()
Generates template with visual attributes for a given geom
- Returns
Initial template with ‘conaffinity’, ‘contype’, and ‘group’ already specified
- Return type
dict
- horizontal_radius()
Returns maximum distance from model root body to any radial point of the model.
Helps us put models programmatically without them flying away due to a huge initial contact force. Must be defined by subclass.
- Returns
radius
- Return type
float
- sanity_check()
Checks if data provided makes sense. Called in __init__() For subclasses to inherit from
- top_offset()
Returns vector from model root body to model top. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
- class robosuite.models.objects.objects.MujocoObject(obj_type='all', duplicate_collision_geoms=True)
Bases:
robosuite.models.base.MujocoModel
Base class for all objects.
We use Mujoco Objects to implement all objects that:
may appear for multiple times in a task
can be swapped between different tasks
Typical methods return copy so the caller can all joints/attributes as wanted
- Parameters
obj_type (str) –
Geom elements to generate / extract for this object. Must be one of:
- ’collision’
Only collision geoms are returned (this corresponds to group 0 geoms)
- ’visual’
Only visual geoms are returned (this corresponds to group 1 geoms)
- ’all’
All geoms are returned
duplicate_collision_geoms (bool) – If set, will guarantee that each collision geom has a visual geom copy
- property actuators
Returns: list: Actuator names for this model
- property bodies
Returns: list: Body names for this model
- property bottom_offset
Returns vector from model root body to model bottom. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
- property contact_geoms
List of names corresponding to the geoms used to determine contact with this model.
- Returns
relevant contact geoms for this model
- Return type
list
- exclude_from_prefixing(inp)
A function that should take in either an ET.Element or its attribute (str) and return either True or False, determining whether the corresponding name / str to @inp should have naming_prefix added to it. Must be defined by subclass.
- Parameters
inp (ET.Element or str) – Element or its attribute to check for prefixing.
- Returns
True if we should exclude the associated name(s) with @inp from being prefixed with naming_prefix
- Return type
bool
- static get_joint_attrib_template()
Returns attribs of free joint
- Returns
Dictionary of default joint attributes
- Return type
dict
- get_obj()
Returns the generated / extracted object, in XML ElementTree form.
- Returns
Object in XML form.
- Return type
ET.Element
- static get_site_attrib_template()
Returns attribs of spherical site used to mark body origin
- Returns
Dictionary of default site attributes
- Return type
dict
- property horizontal_radius
Returns maximum distance from model root body to any radial point of the model.
Helps us put models programmatically without them flying away due to a huge initial contact force. Must be defined by subclass.
- Returns
radius
- Return type
float
- property important_geoms
Returns: dict: (Default is no important geoms; i.e.: empty dict)
- property important_sensors
Returns: dict: (Default is no sensors; i.e.: empty dict)
- property important_sites
Returns: dict:
- obj
Object default site
- property joints
Returns: list: Joint names for this model
- merge_assets(other)
Merges @other’s assets in a custom logic.
- Parameters
other (MujocoXML or MujocoObject) – other xml file whose assets will be merged into this one
- property name
Name for this model. Should be unique.
- Returns
Unique name for this model.
- Return type
str
- property naming_prefix
Generates a standardized prefix to prevent naming collisions
- Returns
Prefix unique to this model.
- Return type
str
- property root_body
Root body name for this model. This should correspond to the top-level body element in the equivalent mujoco xml tree for this object.
- property sensors
Returns: list: Sensor names for this model
- property sites
Returns: list: Site names for this model
- property top_offset
Returns vector from model root body to model top. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
- property visual_geoms
List of names corresponding to the geoms used for visual rendering of this model.
- Returns
relevant visual geoms for this model
- Return type
list
- class robosuite.models.objects.objects.MujocoXMLObject(fname, name, joints='default', obj_type='all', duplicate_collision_geoms=True)
Bases:
robosuite.models.objects.objects.MujocoObject
,robosuite.models.base.MujocoXML
MujocoObjects that are loaded from xml files (by default, inherit all properties (e.g.: name) from MujocoObject class first!)
- Parameters
fname (str) – XML File path
name (str) – Name of this MujocoXMLObject
joints (None or str or list of dict) – each dictionary corresponds to a joint that will be created for this object. The dictionary should specify the joint attributes (type, pos, etc.) according to the MuJoCo xml specification. If “default”, a single free-joint will be automatically generated. If None, no joints will be created.
obj_type (str) –
Geom elements to generate / extract for this object. Must be one of:
- ’collision’
Only collision geoms are returned (this corresponds to group 0 geoms)
- ’visual’
Only visual geoms are returned (this corresponds to group 1 geoms)
- ’all’
All geoms are returned
duplicate_collision_geoms (bool) – If set, will guarantee that each collision geom has a visual geom copy
- property bottom_offset
Returns vector from model root body to model bottom. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
- exclude_from_prefixing(inp)
By default, don’t exclude any from being prefixed
- property horizontal_radius
Returns maximum distance from model root body to any radial point of the model.
Helps us put models programmatically without them flying away due to a huge initial contact force. Must be defined by subclass.
- Returns
radius
- Return type
float
- property top_offset
Returns vector from model root body to model top. Useful for, e.g. placing models on a surface. Must be defined by subclass.
- Returns
(dx, dy, dz) offset vector
- Return type
np.array
robosuite.models.objects.xml_objects module
- class robosuite.models.objects.xml_objects.BottleObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Bottle object
- class robosuite.models.objects.xml_objects.BreadObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Bread loaf object (used in PickPlace)
- class robosuite.models.objects.xml_objects.BreadVisualObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Visual fiducial of bread loaf (used in PickPlace)
Fiducial objects are not involved in collision physics. They provide a point of reference to indicate a position.
- class robosuite.models.objects.xml_objects.CanObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Coke can object (used in PickPlace)
- class robosuite.models.objects.xml_objects.CanVisualObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Visual fiducial of coke can (used in PickPlace)
Fiducial objects are not involved in collision physics. They provide a point of reference to indicate a position.
- class robosuite.models.objects.xml_objects.CerealObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Cereal box object (used in PickPlace)
- class robosuite.models.objects.xml_objects.CerealVisualObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Visual fiducial of cereal box (used in PickPlace)
Fiducial objects are not involved in collision physics. They provide a point of reference to indicate a position.
- class robosuite.models.objects.xml_objects.DoorObject(name, friction=None, damping=None, lock=False)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Door with handle (used in Door)
- Parameters
friction (3-tuple of float) – friction parameters to override the ones specified in the XML
damping (float) – damping parameter to override the ones specified in the XML
lock (bool) – Whether to use the locked door variation object or not
- property important_sites
Returns: dict: In addition to any default sites for this object, also provides the following entries
- ‘handle’
Name of door handle location site
- class robosuite.models.objects.xml_objects.LemonObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Lemon object
- class robosuite.models.objects.xml_objects.MilkObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Milk carton object (used in PickPlace)
- class robosuite.models.objects.xml_objects.MilkVisualObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Visual fiducial of milk carton (used in PickPlace).
Fiducial objects are not involved in collision physics. They provide a point of reference to indicate a position.
- class robosuite.models.objects.xml_objects.PlateWithHoleObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Square plate with a hole in the center (used in PegInHole)
- class robosuite.models.objects.xml_objects.RoundNutObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Round nut (used in NutAssembly)
- property important_sites
Returns: dict: In addition to any default sites for this object, also provides the following entries
- ‘handle’
Name of nut handle location site
- class robosuite.models.objects.xml_objects.SquareNutObject(name)
Bases:
robosuite.models.objects.objects.MujocoXMLObject
Square nut object (used in NutAssembly)
- property important_sites
Returns: dict: In addition to any default sites for this object, also provides the following entries
- ‘handle’
Name of nut handle location site