Robot Model#

Robot Model#

The RobotModel class serves as a direct intermediary class that reads in information from a corresponding robot XML file and also contains relevant hard-coded information from that XML. This represents an arbitrary robot optionally equipped with a mount via the RobotBaseModel class and is the core modeling component of the higher-level Robot class used in simulation.

class robosuite.models.robots.robot_model.RobotModel(fname: str, idn=0)#

Base class for all robot models.

Parameters:
  • fname (str) – Path to relevant xml file from which to create this robot instance

  • idn (int or str) – Number or some other unique identification string for this robot instance

set_base_xpos(pos: ndarray)#

Places the robot on position @pos.

Parameters:

pos (3-array) – (x,y,z) position to place robot base

set_base_ori(rot: ndarray)#

Rotates robot by rotation @rot from its original orientation.

Parameters:

rot (3-array) – (r,p,y) euler angles specifying the orientation for the robot base

set_joint_attribute(attrib: str, values: ndarray, force=True)#

Sets joint attributes, e.g.: friction loss, damping, etc.

Parameters:
  • attrib (str) – Attribute to set for all joints

  • values (n-array) – Values to set for each joint

  • force (bool) – If True, will automatically override any pre-existing value. Otherwise, if a value already exists for this value, it will be skipped

Raises:

AssertionError – [Inconsistent dimension sizes]

add_base(base: RobotBaseModel)#

Mounts a base to the robot. Bases are defined in robosuite.models.bases

add_mount(mount: MountModel)#

Mounts @mount to arm.

Throws error if robot already has a mount or if mount type is incorrect.

Parameters:

mount (MountModel) – mount MJCF model

Raises:

ValueError – [mount already added]

add_mobile_base(mobile_base: MobileBaseModel)#

Mounts @mobile_base to arm.

Throws error if robot already has a mobile base or if mobile base type is incorrect.

Parameters:

base (mobile) – mount MJCF model

Raises:

ValueError – [mobile base already added]

add_leg_base(leg_base: LegBaseModel)#

Mounts @mobile_base to arm.

Throws error if robot already has a mobile base or if mobile base type is incorrect.

Parameters:

base (mobile) – mount MJCF model

Raises:

ValueError – [mobile base already added]

property dof: int#

Defines the number of DOF of the robot

Returns:

robot DOF

Return type:

int

property default_base: str#

Defines the default mount type for this robot that gets added to root body (base)

Returns:

Default base name to add to this robot

Return type:

str

property default_controller_config: Dict[str, str]#

Defines the name of default controller config file in the controllers/config directory for this robot.

Returns:

Dictionary containing arm-specific default controller config names

e.g.: {“right”: “default_panda”, “left”: “default_panda”}

Return type:

dict

property init_qpos: ndarray#

Defines the default rest qpos of this robot

Returns:

Default init qpos of this robot

Return type:

np.array

property base_xpos_offset: Dict[str, ndarray]#

Defines the dict of various (x,y,z) tuple offsets relative to specific arenas placed at (0,0,0) Assumes robot is facing forwards (in the +x direction) when determining offset. Should have entries for each arena case; i.e.: “bins”, “empty”, and “table”)

Returns:

Dict mapping arena names to robot offsets from the global origin (dict entries may also be lambdas

for variable offsets)

Return type:

dict

property _horizontal_radius: float#

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_sites: Dict[str, str]#

Returns: dict: (Default is no important sites; i.e.: empty dict)

property _important_geoms: Dict[str, List[str]]#

Returns: dict: (Default is no important geoms; i.e.: empty dict)

property _important_sensors: Dict[str, str]#

Returns: dict: (Default is no sensors; i.e.: empty dict)

Manipulator Model#

The ManipulatorModel class extends from the base RobotModel class, and represents an armed, mounted robot with an optional gripper attached to its end effector. In conjunction with the corresponding GripperModel class and RobotBaseModel class, this serves as the core modeling component of the higher-level Manipulator class used in simulation.

class robosuite.models.robots.manipulators.manipulator_model.ManipulatorModel(fname: str, idn=0)#

Base class for all manipulator models (robot arm(s) with gripper(s)).

Parameters:
  • fname (str) – Path to relevant xml file from which to create this robot instance

  • idn (int or str) – Number or some other unique identification string for this robot instance

add_gripper(gripper: GripperModel, arm_name: str | None = None)#

Mounts @gripper to arm.

Throws error if robot already has a gripper or gripper type is incorrect.

Parameters:
  • gripper (GripperModel) – gripper MJCF model

  • arm_name (str) – name of arm mount – defaults add to all self.eef_name if not specified

Raises:

ValueError – [Multiple grippers]

property default_gripper: Dict[str, str]#

Defines the default gripper type for this robot that gets added to end effector

Returns:

(Default is no gripper; i.e.: empty dict)

Return type:

dict

property arm_type: str#

Type of robot arm. Should be either “bimanual” or “single” (or something else if it gets added in the future)

Returns:

Type of robot

Return type:

str

property base_xpos_offset: Dict[str, tuple | dict]#

Defines the dict of various (x,y,z) tuple offsets relative to specific arenas placed at (0,0,0) Assumes robot is facing forwards (in the +x direction) when determining offset. Should have entries for each manipulator arena case; i.e.: “bins”, “empty”, and “table”)

Returns:

‘bins’:

(x,y,z) robot offset if placed in bins arena

’empty’:

(x,y,z) robot offset if placed in the empty arena

’table’:

lambda function that takes in table_length and returns corresponding (x,y,z) offset if placed in the table arena

Return type:

dict

property eef_name: Dict[str, str]#

Returns: dict of str: Prefix-adjusted eef name for this robot. If bimanual robot, returns {“left”, “right”}

keyword-mapped eef names

property _important_sites: Dict[str, str]#

Returns: dict: (Default is no important sites; i.e.: empty dict)

Gripper Model#

The GripperModel class serves as a direct intermediary class that reads in information from a corresponding gripper XML file and also contains relevant hard-coded information from that XML. In conjunction with the ManipulatorModel class, this serves as the core modeling component of the higher-level Manipulator class used in simulation.

class robosuite.models.grippers.gripper_model.GripperModel(fname, idn=0)#

Base class for grippers

Parameters:
  • fname (str) – Path to relevant xml file to create this gripper instance

  • idn (int or str) – Number or some other unique identification string for this gripper instance

format_action(action)#

Given (-1,1) abstract control as np-array returns the (-1,1) control signals for underlying actuators as 1-d np array

property speed#

How quickly the gripper opens / closes

Returns:

Speed of the gripper

Return type:

float

property dof#

Defines the number of DOF of the gripper

Returns:

gripper DOF

Return type:

int

property init_qpos#

Defines the default rest (open) qpos of the gripper

Returns:

Default init qpos of this gripper

Return type:

np.array

property _important_sites#

Sites used to aid visualization by human. (usually “grip_site” and “grip_cylinder”) (and should be hidden from robots)

Returns:

‘grip_site’:

Name of grip actuation intersection location site

’grip_cylinder’:

Name of grip actuation z-axis location site

’ee’:

Name of end effector site

’ee_x’:

Name of end effector site (x-axis)

’ee_y’:

Name of end effector site (y-axis)

’ee_z’:

Name of end effector site (z-axis)

Return type:

dict

property _important_geoms#

Geoms corresponding to important components of the gripper (by default, left_finger, right_finger, left_fingerpad, right_fingerpad). Note that these are the raw string names directly pulled from a gripper’s corresponding XML file, NOT the adjusted name with an auto-generated naming prefix

Note that this should be a dict of lists.

Returns:

Raw XML important geoms, where each set of geoms are grouped as a list and are organized by keyword string entries into a dict

Return type:

dict of list

property _important_sensors#

Sensor names for each gripper (usually “force_ee” and “torque_ee”)

Returns:

‘force_ee’:

Name of force eef sensor for this gripper

’torque_ee’:

Name of torque eef sensor for this gripper

Return type:

dict

Robot Base Model#

The RobotBaseModel class represents the base of the robot. User can use add_base method in the RobotModel class to add a base model to the robot.

There are mainly three types of base models: MountModel, MobileBaseModel, and LegBaseModel.

class robosuite.models.bases.robot_base_model.RobotBaseModel(fname: str, idn=0)#

Base class for mounts that will be attached to robots. Note that this model’s root body will be directly appended to the robot’s root body, so all offsets should be taken relative to that.

Parameters:
  • fname (str) – Path to relevant xml file to create this mount instance

  • idn (int or str) – Number or some other unique identification string for this gripper instance

property top_offset: array#

Returns vector from model root body to model top. This should correspond to the distance from the root body to the actual mounting surface location of this mount.

Returns:

(dx, dy, dz) offset vector

Return type:

np.array

property horizontal_radius: float#

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 naming_prefix: str#

Generates a standardized prefix to prevent naming collisions

Returns:

Prefix unique to this model.

Return type:

str

property _important_sites: Dict[str, str]#

Returns: dict: (Default is no important sites; i.e.: empty dict)

property _important_geoms: Dict[str, List[str]]#

Returns: dict: (Default is no important geoms; i.e.: empty dict)

property _important_sensors: Dict[str, str]#

Returns: dict: (Default is no sensors; i.e.: empty dict)