MuJoCo Visualizer#
JAXsim provides a simple interface with MuJoCo’s visualizer. The visualizer is a separate process that communicates with the main simulation process. This allows for the simulation to run at full speed while the visualizer can run at a different frame rate.
Loaders#
- class jaxsim.mujoco.loaders.ModelToMjcf[source]#
Class to convert a URDF/SDF file or a ROD model to a Mujoco MJCF string.
- static convert(model, considered_joints=None, plane_normal=(0, 0, 1), heightmap=None, heightmap_samples_xy=(101, 101), cameras=())[source]#
Convert a model to a Mujoco MJCF string.
- Parameters:
model (
str
|Path
|Model
) – The URDF/SDF file or ROD model to convert.considered_joints (
list
[str
] |None
) – The list of joint names to consider in the conversion.plane_normal (
tuple
[float
,float
,float
]) – The normal vector of the plane.heightmap (
bool
|None
) – Whether to generate a heightmap.heightmap_samples_xy (
tuple
[int
,int
]) – The number of points in the heightmap grid.cameras (
MujocoCamera
|Sequence
[MujocoCamera
] |dict
[str
,str
] |Sequence
[dict
[str
,str
]]) – The custom cameras to add to the scene.
- Return type:
tuple
[str
,dict
[str
,Any
]]- Returns:
A tuple containing the MJCF string and the dictionary of assets.
- class jaxsim.mujoco.loaders.RodModelToMjcf[source]#
Class to convert a ROD model to a Mujoco MJCF string.
- static add_floating_joint(urdf_string, base_link_name, floating_joint_name='world_to_base')[source]#
Add a floating joint to a URDF string.
- Parameters:
urdf_string (
str
) – The URDF string to modify.base_link_name (
str
) – The name of the base link to attach the floating joint.floating_joint_name (
str
) – The name of the floating joint to add.
- Returns:
The modified URDF string.
- Return type:
str
- static assets_from_rod_model(rod_model)[source]#
Generate a dictionary of assets from a ROD model.
- Parameters:
rod_model (
Model
) – The ROD model to extract the assets from.- Returns:
A dictionary of assets.
- Return type:
dict
- static convert(rod_model, considered_joints=None, plane_normal=(0, 0, 1), heightmap=None, heightmap_samples_xy=(101, 101), cameras=())[source]#
Convert a ROD model to a Mujoco MJCF string.
- Parameters:
rod_model (
Model
) – The ROD model to convert.considered_joints (
list
[str
] |None
) – The list of joint names to consider in the conversion.plane_normal (
tuple
[float
,float
,float
]) – The normal vector of the plane.heightmap (
bool
|None
) – Whether to generate a heightmap.heightmap_samples_xy (
tuple
[int
,int
]) – The number of points in the heightmap grid.cameras (
MujocoCamera
|Sequence
[MujocoCamera
] |dict
[str
,str
] |Sequence
[dict
[str
,str
]]) – The custom cameras to add to the scene.
- Return type:
tuple
[str
,dict
[str
,Any
]]- Returns:
A tuple containing the MJCF string and the dictionary of assets.
- class jaxsim.mujoco.loaders.SdfToMjcf[source]#
Class to convert a SDF file to a Mujoco MJCF string.
- static convert(sdf, considered_joints=None, model_name=None, plane_normal=(0, 0, 1), heightmap=None, cameras=())[source]#
Convert a SDF file to a Mujoco MJCF string.
- Parameters:
sdf (
str
|Path
) – The SDF file to convert.considered_joints (
list
[str
] |None
) – The list of joint names to consider in the conversion.model_name (
str
|None
) – The name of the model to convert.plane_normal (
tuple
[float
,float
,float
]) – The normal vector of the plane.heightmap (
bool
|None
) – Whether to generate a heightmap.cameras (
MujocoCamera
|Sequence
[MujocoCamera
] |dict
[str
,str
] |Sequence
[dict
[str
,str
]]) – The list of cameras to add to the scene.
- Returns:
A tuple containing the MJCF string and the assets dictionary.
- Return type:
tuple
- class jaxsim.mujoco.loaders.UrdfToMjcf[source]#
Class to convert a URDF file to a Mujoco MJCF string.
- static convert(urdf, considered_joints=None, model_name=None, plane_normal=(0, 0, 1), heightmap=None, cameras=())[source]#
Convert a URDF file to a Mujoco MJCF string.
- Parameters:
urdf (
str
|Path
) – The URDF file to convert.considered_joints (
list
[str
] |None
) – The list of joint names to consider in the conversion.model_name (
str
|None
) – The name of the model to convert.plane_normal (
tuple
[float
,float
,float
]) – The normal vector of the plane.heightmap (
bool
|None
) – Whether to generate a heightmap.cameras (
MujocoCamera
|Sequence
[MujocoCamera
] |dict
[str
,str
] |Sequence
[dict
[str
,str
]]) – The list of cameras to add to the scene.
- Returns:
A tuple containing the MJCF string and the assets dictionary.
- Return type:
tuple
- jaxsim.mujoco.loaders.load_rod_model(model_description, is_urdf=None, model_name=None)[source]#
Load a ROD model from a URDF/SDF file or a ROD model.
- Parameters:
model_description (
str
|Path
|Model
) – The URDF/SDF file or ROD model to load.is_urdf (
bool
|None
) – Whether to force parsing the model description as a URDF file.model_name (
str
|None
) – The name of the model to load from the resource.
- Returns:
The loaded ROD model.
- Return type:
rod.Model
Model#
- class jaxsim.mujoco.model.MujocoModelHelper(model, data=None)[source]#
Helper class to create and interact with Mujoco models and data objects.
- Parameters:
model (mj.MjModel)
data (mj.MjData | None)
- base_orientation(dcm=False)[source]#
Return the orientation of the base link.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]- Parameters:
dcm (bool)
- base_position()[source]#
Return the 3D position of the base link.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]
- body_orientation(body_name, dcm=False)[source]#
Return the orientation of a body.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]- Parameters:
body_name (str)
dcm (bool)
- body_position(body_name)[source]#
Return the position of a body.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]- Parameters:
body_name (str)
- static build_from_xml(mjcf_description, assets=None, heightmap=None, heightmap_name='terrain', heightmap_radius_xy=(1.0, 1.0))[source]#
Build a Mujoco model from an MJCF description.
- Parameters:
mjcf_description (
str
|Path
) – A string containing the XML description of the Mujoco model or a path to a file containing the XML description.assets (
dict
[str
,Any
] |None
) – An optional dictionary containing the assets of the model.heightmap (
Callable
[[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]] |None
) – A function in two variables that returns the height of a terrain in the specified coordinate point.heightmap_name (
str
) – The default name of the heightmap in the MJCF description to load the corresponding configuration.heightmap_radius_xy (
tuple
[float
,float
]) – The extension of the heightmap in the x-y surface corresponding to the plane over which the grid of the sampled heightmap is generated.
- Return type:
- Returns:
A MujocoModelHelper object.
- geometry_orientation(geometry_name, dcm=False)[source]#
Return the orientation of a geometry.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]- Parameters:
geometry_name (str)
dcm (bool)
- geometry_position(geometry_name)[source]#
Return the position of a geometry.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]- Parameters:
geometry_name (str)
- gravity()[source]#
Return the 3D gravity vector.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]
- joint_dofs(joint_name)[source]#
Return the number of DoFs of a joint.
- Return type:
int
- Parameters:
joint_name (str)
- joint_position(joint_name)[source]#
Return the position of a joint.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]- Parameters:
joint_name (str)
- joint_positions(joint_names=None)[source]#
Return the positions of the joints.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]- Parameters:
joint_names (list[str] | None)
- set_base_orientation(orientation, dcm=False)[source]#
Set the 3D position of the base link.
- Return type:
None
- Parameters:
orientation (ndarray[tuple[int, ...], dtype[_ScalarType_co]])
dcm (bool)
- set_base_position(position)[source]#
Set the 3D position of the base link.
- Return type:
None
- Parameters:
position (ndarray[tuple[int, ...], dtype[_ScalarType_co]])
- set_joint_position(joint_name, position)[source]#
Set the position of a joint.
- Return type:
None
- Parameters:
joint_name (str)
position (ndarray[tuple[int, ...], dtype[_ScalarType_co]] | float)
- jaxsim.mujoco.model.generate_hfield(heightmap, samples_xy=(11, 11), radius_xy=(1.0, 1.0))[source]#
Generate an array with elevation points sampled from a heightmap function.
The map will have the following format:
` heightmap[0, 0] heightmap[0, 1] ... heightmap[0, size[1]-1] heightmap[1, 0] heightmap[1, 1] ... heightmap[1, size[1]-1] ... heightmap[size[0]-1, 0] heightmap[size[0]-1, 1] ... heightmap[size[0]-1, size[1]-1] `
- Parameters:
heightmap (
Callable
[[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]) – A function that takes two arguments (x, y) and returns the height at that point.samples_xy (
tuple
[int
,int
]) – A tuple of two integers representing the size of the grid.radius_xy (
tuple
[float
,float
]) – A tuple of two floats representing extension of the heightmap in the x-y surface corresponding to the area over which the grid of the sampled heightmap is generated.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]- Returns:
A flat array of the sampled terrain heightmap.
Visualizer#
- class jaxsim.mujoco.visualizer.MujocoVideoRecorder(model, data, fps=30, width=None, height=None, **kwargs)[source]#
Video recorder for the MuJoCo passive viewer.
- Parameters:
model (MjModel)
data (MjData)
fps (int)
width (int | None)
height (int | None)
- static compute_down_sampling(original_fps, target_min_fps)[source]#
Return the integer down-sampling factor to reach at least the target fps.
- Parameters:
original_fps (
int
) – The original fps.target_min_fps (
int
) – The target minimum fps.
- Return type:
int
- Returns:
The down-sampling factor.
- record_frame(camera_name='track')[source]#
Store a frame in the buffer.
- Return type:
None
- Parameters:
camera_name (str)
- render_frame(camera_name='track')[source]#
Render a frame.
- Return type:
ndarray
[tuple
[int
,...
],dtype
[TypeVar
(_ScalarType_co
, bound=generic
, covariant=True)]]- Parameters:
camera_name (str)
- class jaxsim.mujoco.visualizer.MujocoVisualizer(model=None, data=None)[source]#
Visualizer for the MuJoCo passive viewer.
- Parameters:
model (MjModel | None)
data (MjData | None)
- open(model=None, data=None, *, show_left_ui=False, close_on_exit=True, lookat=None, distance=None, azimuth=None, elevation=None)[source]#
Context manager to open the Mujoco passive viewer. :rtype:
AbstractContextManager
[Handle
]Note
Refer to the Mujoco documentation for details of the camera options: https://mujoco.readthedocs.io/en/stable/XMLreference.html#visual-global
- Parameters:
model (MjModel | None)
data (MjData | None)
show_left_ui (bool)
close_on_exit (bool)
lookat (Sequence[float | int] | ndarray[tuple[int, ...], dtype[_ScalarType_co]] | None)
distance (float | int | ndarray[tuple[int, ...], dtype[_ScalarType_co]] | None)
azimuth (float | int | ndarray[tuple[int, ...], dtype[_ScalarType_co]] | None)
elevation (float | int | ndarray[tuple[int, ...], dtype[_ScalarType_co]] | None)
- Return type:
AbstractContextManager[Handle]
- open_viewer(model=None, data=None, show_left_ui=False)[source]#
Open a viewer.
- Return type:
Handle
- Parameters:
model (MjModel | None)
data (MjData | None)
show_left_ui (bool)
- static setup_viewer_camera(viewer, *, lookat, distance=None, azimuth=None, elevation=None)[source]#
Configure the initial viewpoint of the Mujoco passive viewer.
Note
Refer to the Mujoco documentation for details of the camera options: https://mujoco.readthedocs.io/en/stable/XMLreference.html#visual-global
- Return type:
Handle
- Returns:
The viewer with configured camera.
- Parameters:
viewer (Handle)
lookat (Sequence[float | int] | ndarray[tuple[int, ...], dtype[_ScalarType_co]] | None)
distance (float | int | ndarray[tuple[int, ...], dtype[_ScalarType_co]] | None)
azimuth (float | int | ndarray[tuple[int, ...], dtype[_ScalarType_co]] | None)
elevation (float | int | ndarray[tuple[int, ...], dtype[_ScalarType_co]] | None)