hyphi_gym.utils.mujoco_utils
#
Module Contents#
Classes#
Access MujocoObject object names and ids of the current MuJoCo model. |
Functions#
|
Returns all joint positions and velocities associated with a robot. |
|
For torque actuators it copies the action into mujoco ctrl field. |
|
Update the position of the mocap body with the desired action. |
|
Resets the mocap welds that we use for actuation. |
|
Resets the position and orientation of the mocap bodies to the same |
|
Return the Jacobian' translational component of the end-effector of |
|
Return the Jacobian' rotational component of the end-effector of |
|
Set the joint positions (qpos) of the model. |
|
Set the joints linear and angular (qvel) of the model. |
|
Return the joints position and orientation (qpos) of the model. |
|
Return the joints linear and angular velocities (qvel) of the model. |
|
|
|
|
|
|
|
|
|
|
|
|
|
Convert Rotation Matrix to Euler Angles. |
|
Attributes#
- hyphi_gym.utils.mujoco_utils.MJ_OBJ_TYPES = ['mjOBJ_BODY', 'mjOBJ_JOINT', 'mjOBJ_GEOM', 'mjOBJ_SITE', 'mjOBJ_CAMERA', 'mjOBJ_ACTUATOR',...#
- hyphi_gym.utils.mujoco_utils.robot_get_obs(model, data, joint_names)#
Returns all joint positions and velocities associated with a robot.
- hyphi_gym.utils.mujoco_utils.ctrl_set_action(model, data, action)#
For torque actuators it copies the action into mujoco ctrl field. For position actuators it sets the target relative to the current qpos.
- hyphi_gym.utils.mujoco_utils.mocap_set_action(model, data, action)#
Update the position of the mocap body with the desired action.
The action controls the robot using mocaps. Specifically, bodies on the robot (for example the gripper wrist) is controlled with mocap bodies. In this case the action is the desired difference in position and orientation (quaternion), in world coordinates, of the target body. The mocap is positioned relative to the target body according to the delta, and the MuJoCo equality constraint optimizer tries to center the welded body on the mocap.
- hyphi_gym.utils.mujoco_utils.reset_mocap_welds(model, data)#
Resets the mocap welds that we use for actuation.
- hyphi_gym.utils.mujoco_utils.reset_mocap2body_xpos(model, data)#
Resets the position and orientation of the mocap bodies to the same values as the bodies they’re welded to.
- hyphi_gym.utils.mujoco_utils.get_site_jacp(model, data, site_id)#
Return the Jacobian’ translational component of the end-effector of the corresponding site id.
- hyphi_gym.utils.mujoco_utils.get_site_jacr(model, data, site_id)#
Return the Jacobian’ rotational component of the end-effector of the corresponding site id.
- hyphi_gym.utils.mujoco_utils.set_joint_qpos(model, data, name, value)#
Set the joint positions (qpos) of the model.
- hyphi_gym.utils.mujoco_utils.set_joint_qvel(model, data, name, value)#
Set the joints linear and angular (qvel) of the model.
- hyphi_gym.utils.mujoco_utils.get_joint_qpos(model, data, name)#
Return the joints position and orientation (qpos) of the model.
- hyphi_gym.utils.mujoco_utils.get_joint_qvel(model, data, name)#
Return the joints linear and angular velocities (qvel) of the model.
- hyphi_gym.utils.mujoco_utils.get_site_xpos(model, data, name)#
- hyphi_gym.utils.mujoco_utils.get_site_xvelp(model, data, name)#
- hyphi_gym.utils.mujoco_utils.get_site_xvelr(model, data, name)#
- hyphi_gym.utils.mujoco_utils.set_mocap_pos(model, data, name, value)#
- hyphi_gym.utils.mujoco_utils.set_mocap_quat(model: mujoco.MjModel, data: mujoco.MjData, name: str, value)#
- hyphi_gym.utils.mujoco_utils.get_site_xmat(model: mujoco.MjModel, data: mujoco.MjData, name: str)#
- hyphi_gym.utils.mujoco_utils._FLOAT_EPS#
- hyphi_gym.utils.mujoco_utils._EPS4#
- hyphi_gym.utils.mujoco_utils.mat2euler(mat)#
Convert Rotation Matrix to Euler Angles.
See rotation.py for notes
- hyphi_gym.utils.mujoco_utils.extract_mj_names(model: mujoco.MjModel, obj_type: mujoco.mjtObj) tuple[Union[tuple[str, Ellipsis], tuple[]], dict[str, int], dict] #
- class hyphi_gym.utils.mujoco_utils.MujocoModelNames(model: mujoco.MjModel)#
Access MujocoObject object names and ids of the current MuJoCo model. This class supports access to the names and ids of the following mjObj types: mjOBJ_BODY mjOBJ_JOINT mjOBJ_GEOM mjOBJ_SITE mjOBJ_CAMERA mjOBJ_ACTUATOR mjOBJ_SENSOR The properties provided for each <mjObj> are: - <mjObj>_names: list of the mjObj names in the model of type mjOBJ_FOO. - <mjObj>_name2id: dictionary with name of the mjObj as keys and id of the mjObj as values. - <mjObj>_id2name: dictionary with id of the mjObj as keys and name of the mjObj as values.
- property body_names#
- property body_name2id#
- property body_id2name#
- property joint_names#
- property joint_name2id#
- property joint_id2name#
- property geom_names#
- property geom_name2id#
- property geom_id2name#
- property site_names#
- property site_name2id#
- property site_id2name#
- property camera_names#
- property camera_name2id#
- property camera_id2name#
- property actuator_names#
- property actuator_name2id#
- property actuator_id2name#
- property sensor_names#
- property sensor_name2id#
- property sensor_id2name#