--- tags: Robosuite --- # Robosuite ## Todo - [x] add textured mesh in env - [x] add my mesh - [x] textured - [x] un-textured - [x] add multiple mesh in the env - [x] design my env ## installation - official : https://robosuite.ai/docs/installation.html ## load textured mesh .stl format don't support textured mesh while .msh format supports it #### convert .obj to .msh - source : https://github.com/sklaw/obj_2_mujoco_msh 1. `convert_obj_to_mujoco_msh.py` :::spoiler ```python import struct import os import sys if __name__ == "__main__": obj_f_name = sys.argv[1] assert obj_f_name[-4:] == ".obj" and os.path.exists(obj_f_name) msh_f_name = obj_f_name[:-4] + ".msh" v = [] vt = [] vn = [] f = [] obj = open(obj_f_name, 'r') for line in obj: arr = line.split() if len(arr) == 0: continue if arr[0] == '#': continue if arr[0] == 'v': assert len(arr)==4 v.append([float(arr[i]) for i in range(1, 4)]) elif arr[0] == 'vt': assert len(arr) == 3 vt.append([float(arr[i]) for i in range(1, 3)]) elif arr[0] == 'vn': assert len(arr) == 4 vn.append([float(arr[i]) for i in range(1, 4)]) elif arr[0] == 'f': tmp = [arr[i].split("/") for i in range(1,len(arr))] for i in range(1, len(tmp)-1): f.append([tmp[0], tmp[i], tmp[i+1]]) else: print(arr) output_v = [] output_vn = [] output_vt = [] output_f = [] for i in f: assert len(i) == 3 for j in i: v_idx = int(j[0])-1 output_v.append(v[v_idx]) if len(j) >= 2: vt_idx = int(j[1]) - 1 output_vt.append(vt[vt_idx]) if len(j) >= 3: vn_idx = int(j[2]) - 1 output_vn.append(vn[vn_idx]) output_f.append([len(output_v)-3, len(output_v)-2, len(output_v)-1]) print("len(v)=", len(output_v)) print("len(vn)=", len(output_vn)) print("len(vt)=", len(output_vt)) print("len(f)=", len(output_f)) out = open(msh_f_name, 'wb') integer_packing = "=i" float_packing = "=f" def int_to_bytes(input): assert type(input) == int return struct.pack(integer_packing, input) def float_to_bytes(input): assert type(input) == float return struct.pack(float_packing, input) out.write(int_to_bytes(len(output_v))) out.write(int_to_bytes(len(output_vn))) out.write(int_to_bytes(len(output_vt))) out.write(int_to_bytes(len(output_f))) for i in output_v: for j in range(3): out.write(float_to_bytes(i[j])) for i in output_vn: for j in range(3): out.write(float_to_bytes(i[j])) for i in output_vt: out.write(float_to_bytes(i[0])) out.write(float_to_bytes(1-i[1])) for i in output_f: for j in range(3): out.write(int_to_bytes(i[j])) out.close() print("actual file size=", os.path.getsize(msh_f_name)) expected_file_size = 16 + 12*(len(output_v) + len(output_vn) + len(output_f)) + 8*len(output_vt) print("expected_file_size=", expected_file_size) ``` ::: usage : ```shell $ python convert_obj_to_mujoco_msh.py [.obj file path] ``` 2. use the script below to write to xml xml template can be assigned by the given `.msh` file path and the corresponding texture map (`.png`) - Mujoco engine will load geometry (`.msh`) and texture seperately (`.png`), so we still need to add the texture map path name in the xml file in the <texture></texture> field - `write_to_xml.py` ```python import sys import os obj_name = sys.argv[1] msh_path = sys.argv[2] texture_path = sys.argv[3] xml_path = sys.argv[4] xml_template = f'''<mujoco model="{obj_name}"> <asset> <mesh file="{msh_path}" name="{obj_name}_mesh" scale="0.8 0.8 0.8"/> <texture file="{texture_path}" name="tex-{obj_name}" type="2d"/> <material name="{obj_name}" reflectance="0.7" texrepeat="5 5" texture="tex-{obj_name}" texuniform="true"/> </asset> <worldbody> <body> <body name="object"> <geom pos="0 0 0" mesh="{obj_name}_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="{obj_name}" group="0" condim="4"/> </body> <site rgba="0 0 0 0" size="0.005" pos="0 0 -0.045" name="bottom_site"/> <site rgba="0 0 0 0" size="0.005" pos="0 0 0.03" name="top_site"/> <site rgba="0 0 0 0" size="0.005" pos="0.03 0.03 0" name="horizontal_radius_site"/> </body> </worldbody> </mujoco>''' with open(xml_path, 'w') as f: f.writelines(xml_template) ``` usage : ```shell $ python write_to_xml.py [obj name] [msh path] [texture path] [xml output path] ``` 3. run the shell script below to automatically execute the two python code above - run.sh ```shell # /bin/bash if [ $# -ge 1 ]; then if [ $1 = "obj2msh" ]; then target=$2 obj_path="" msh_path="" tex_path="" xml_path="" if [ $target = "ycb" ]; then obj_names=("adjustable-wrench" "extra-large-clamp" "hammer" "large-clamp" "medium-clamp" "mug" "pitcher-base" "power-drill" "scissors" "spatula" "windex-bottle") for obj_name in "${obj_names[@]}" do obj_path="meshes/ycb_eval_data/hanging_eval/$obj_name/textured.obj" msh_path="meshes/ycb_eval_data/hanging_eval/$obj_name/textured.msh" tex_path="meshes/ycb_eval_data/hanging_eval/$obj_name/texture_map.png" xml_path="ycb_xml/$obj_name.xml" # conversion python3 convert_obj_to_msh.py $obj_path # write to xml python3 write_to_xml.py $obj_name "../$msh_path" "../$tex_path" "$xml_path" done elif [ $target = "hook" ]; then obj_name=$3 obj_path="meshes/hook_wall/hanging_eval/$3/textured.obj" msh_path="meshes/hook_wall/hanging_eval/$3/textured.msh" tex_path="meshes/hook_wall/hanging_eval/$3/texture_map.png" xml_path="hook_xml/$3.xml" # conversion python3 convert_obj_to_msh.py $obj_path # write to xml python3 write_to_xml.py $obj_name $msh_path $tex_path $xml_path elif [ $target = "cook" ]; then ls ./meshes/cooking_utensil/ obj_names=( $( ls ./meshes/cooking_utensil/ ) ) for obj_name in "${obj_names[@]}" do obj_path="meshes/cooking_utensil/$obj_name/base.obj" msh_path="meshes/cooking_utensil/$obj_name/base.msh" tex_path="../textures/dark-wood.png" xml_path="cooking_utensil_xml/cooking_utensil_$obj_name.xml" # conversion python3 convert_obj_to_msh.py $obj_path # write to xml python3 write_to_xml.py $obj_name "../$msh_path" "../$tex_path" "$xml_path" done fi else echo "wrong function : $1" fi else echo 'function num should be equal or greater than 2' fi ``` usage : ```shell $ ./run.sh obj2msh ycb hammer # ``` #### load xml that contains msh info - object class : ```python from robosuite.models.objects import MujocoXMLObject ``` - load model : `xml_path` is the xml file output by the script above ```python model = MujocoXMLObject( xml_path_completion(xml_path), name=name, joints=[dict(type="free", damping="0.0005")], obj_type="all", duplicate_collision_geoms=True,) ``` #### put msh in `Lift` task - modify the `_load_model()` function in lift.py ```python self.cube = MujocoXMLObject( xml_path_completion("objects/hammer.xml"), name='hammer', joints=[dict(type="free", damping="0.0005")], obj_type="all", duplicate_collision_geoms=True,) # Create placement initializer if self.placement_initializer is not None: self.placement_initializer.reset() self.placement_initializer.add_objects(self.cube) else: self.placement_initializer = UniformRandomSampler( name="ObjectSampler", mujoco_objects=self.cube, x_range=[-0.03, 0.03], y_range=[-0.03, 0.03], rotation=None, ensure_object_boundary_in_range=False, ensure_valid_placement=True, reference_pos=self.table_offset, z_offset=0.01, ) self.model = ManipulationTask( mujoco_arena=mujoco_arena, mujoco_robots=[robot.robot_model for robot in self.robots], mujoco_objects=self.cube, ) ``` ![](https://i.imgur.com/hvGNPWf.jpg) ## add my mesh #### output un-textured mesh - use open3d API to do so #### output textured mesh - convert point cloud to textured mesh ```python import pymeshlab # get the point cloud and estimate normals # convert to mesh clustering_pcd.estimate_normals() points = clustering_pcd_pts colors = np.hstack((clustering_pcd_colors, np.ones((clustering_pcd_colors.shape[0], 1)))) normals = np.asarray(clustering_pcd.normals) print(points.shape, colors.shape, normals.shape) m = pymeshlab.Mesh(points, v_normals_matrix=normals, v_color_matrix=colors ) # color is N x 4 with alpha info ms = pymeshlab.MeshSet() ms.add_mesh(m, "pc_scan") ms.generate_surface_reconstruction_screened_poisson(depth=6, scale=1.5) # not familiar with the crop API, but I'm sure it's doable # now we generate UV map; there are a couple options here but this is a naive way ms.compute_texcoord_parametrization_triangle_trivial_per_wedge(textdim = 1024) # create texture using UV map and vertex colors ms.compute_texmap_from_color(textname=f"{obj_name}") # textname will be filename of a png, should not be a full path # texture file won't be saved until you save the mesh ms.save_current_mesh(os.path.join(pcd_input_dir, f'{obj_name}/{obj_name}.obj')) print(f'{obj_name}/{obj_name}.obj saved') ``` notice that - https://pymeshlab.readthedocs.io/en/latest/filter_list.html - compute_texcoord_parametrization_triangle_trivial_per_wedge - texdim #### convert .obj ( .mtl and .mtl) files into .msh files ## add multiple object in one task - todo : how to let the objects controlled by gravity ## my env - extend `table_arena.xml` :::spoiler ```xml <mujoco model="table_arena"> <asset> <!-- hook mesh --> <mesh file="meshes/hook_wall/bar_with_two_hooks/base.msh" name="bar_with_two_hooks_mesh" scale="0.3 0.25 0.3"/> <texture file="meshes/hook_wall/bar_with_two_hooks/dark-wood.png" name="tex-bar_with_two_hooks" type="2d"/> <material name="bar_with_two_hooks" reflectance="0.7" texrepeat="5 5" texture="tex-bar_with_two_hooks" texuniform="true"/> <!-- bar mesh --> <mesh file="meshes/hook_wall/two_bars/base.msh" name="two_bars_mesh" scale="0.2 0.2 0.3"/> <texture file="meshes/hook_wall/two_bars/dark-wood.png" name="tex-two_bars" type="2d"/> <material name="two_bars" reflectance="0.7" texrepeat="5 5" texture="tex-two_bars" texuniform="true"/> <!-- power-drill mesh --> <mesh file="my_objects/ycb_eval_data/hanging_eval/power-drill/textured.msh" name="power-drill_mesh" scale="0.8 0.8 0.8"/> <texture file="my_objects/ycb_eval_data/hanging_eval/power-drill/texture_map.png" name="tex-power-drill" type="2d"/> <material name="power-drill" reflectance="0.7" texrepeat="5 5" texture="tex-power-drill" texuniform="true"/> <!-- spatula mesh --> <mesh file="my_objects/ycb_eval_data/hanging_eval/spatula/textured.msh" name="spatula_mesh" scale="0.8 0.8 0.8"/> <texture file="my_objects/ycb_eval_data/hanging_eval/spatula/texture_map.png" name="tex-spatula" type="2d"/> <material name="spatula" reflectance="0.7" texrepeat="5 5" texture="tex-spatula" texuniform="true"/> <!-- adjustable wrench mesh --> <mesh file="my_objects/ycb_eval_data/hanging_eval/adjustable-wrench/textured.msh" name="adjustable-wrench_mesh" scale="0.8 0.8 0.8"/> <texture file="my_objects/ycb_eval_data/hanging_eval/adjustable-wrench/texture_map.png" name="tex-adjustable-wrench" type="2d"/> <material name="adjustable-wrench" reflectance="0.7" texrepeat="5 5" texture="tex-adjustable-wrench" texuniform="true"/> <!-- adjustable wrench mesh --> <mesh file="my_objects/ycb_eval_data/hanging_eval/hammer/textured.msh" name="hammer_mesh" scale="0.8 0.8 0.8"/> <texture file="my_objects/ycb_eval_data/hanging_eval/hammer/texture_map.png" name="tex-hammer" type="2d"/> <material name="hammer" reflectance="0.7" texrepeat="5 5" texture="tex-hammer" texuniform="true"/> <!-- mug mesh --> <mesh file="my_objects/ycb_eval_data/hanging_eval/mug/textured.msh" name="mug_mesh" scale="0.8 0.8 0.8"/> <texture file="my_objects/ycb_eval_data/hanging_eval/mug/texture_map.png" name="tex-mug" type="2d"/> <material name="mug" reflectance="0.7" texrepeat="5 5" texture="tex-mug" texuniform="true"/> <!-- windex-bottle mesh --> <mesh file="my_objects/ycb_eval_data/hanging_eval/windex-bottle/textured.msh" name="windex-bottle_mesh" scale="0.8 0.8 0.8"/> <texture file="my_objects/ycb_eval_data/hanging_eval/windex-bottle/texture_map.png" name="tex-windex-bottle" type="2d"/> <material name="windex-bottle" reflectance="0.7" texrepeat="5 5" texture="tex-windex-bottle" texuniform="true"/> <!-- pitcher-base mesh --> <mesh file="my_objects/ycb_eval_data/hanging_eval/pitcher-base/textured.msh" name="pitcher-base_mesh" scale="0.8 0.8 0.8"/> <texture file="my_objects/ycb_eval_data/hanging_eval/pitcher-base/texture_map.png" name="tex-pitcher-base" type="2d"/> <material name="pitcher-base" reflectance="0.7" texrepeat="5 5" texture="tex-pitcher-base" texuniform="true"/> <!-- my-scissor mesh --> <mesh file="my_objects/tt_scissor/tt_scissor_untextured.msh" name="tt_scissor_mesh" scale="0.8 0.8 0.8"/> <!-- <texture file="my_objects/tt_scissor/tt_scissor.png" name="tex-tt_scissor" type="2d"/> <material name="tt_scissor" reflectance="0.7" texrepeat="5 5" texture="tex-tt_scissor" texuniform="true"/> --> <!-- ceramic table texture and material--> <texture builtin="gradient" height="256" rgb1=".9 .9 1." rgb2=".2 .3 .4" type="skybox" width="256"/> <texture file="../textures/wood-tiles.png" type="2d" name="texplane"/> <material name="floorplane" reflectance="0.01" shininess="0.0" specular="0.0" texrepeat="2 2" texture="texplane" texuniform="true"/> <!-- ceramic table texture and material--> <texture file="../textures/ceramic.png" type="cube" name="tex-ceramic"/> <material name="table_ceramic" reflectance="0.0" shininess="0.0" specular="0.2" texrepeat="1 1" texture="tex-ceramic" /> <!-- steel legs --> <texture file="../textures/steel-brushed.png" type="cube" name="tex-steel-brushed"/> <material name="table_legs_metal" reflectance="0.8" shininess="0.8" texrepeat="1 1" texture="tex-steel-brushed" /> <!-- plaster walls --> <texture file="../textures/cream-plaster.png" type="2d" name="tex-cream-plaster"/> <material name="walls_mat" reflectance="0.0" shininess="0.1" specular="0.1" texrepeat="3 3" texture="tex-cream-plaster" texuniform="true" /> <!-- added table texture and material for domain randomization --> <texture name="textable" builtin="flat" height="512" width="512" rgb1="0.5 0.5 0.5" rgb2="0.5 0.5 0.5"/> <material name="table_mat" texture="textable" /> </asset> <worldbody> <!-- Floor --> <geom condim="3" material="floorplane" name="floor" pos="0 0 0" size="3 3 .125" type="plane"/> <!-- Walls (visual only) --> <!-- <geom pos="-1.25 2.25 1.5" quat="0.6532815 0.6532815 0.2705981 0.2705981" size="1.06 1.5 0.01" type="box" conaffinity="0" contype="0" group="1" name="wall_leftcorner_visual" material="walls_mat"/> <geom pos="-1.25 -2.25 1.5" quat="0.6532815 0.6532815 -0.2705981 -0.2705981" size="1.06 1.5 0.01" type="box" conaffinity="0" contype="0" group="1" name="wall_rightcorner_visual" material="walls_mat"/> <geom pos="1.25 3 1.5" quat="0.7071 0.7071 0 0" size="1.75 1.5 0.01" type="box" conaffinity="0" contype="0" group="1" name="wall_left_visual" material="walls_mat"/> <geom pos="1.25 -3 1.5" quat="0.7071 -0.7071 0 0" size="1.75 1.5 0.01" type="box" conaffinity="0" contype="0" group="1" name="wall_right_visual" material="walls_mat"/> <geom pos="-2 0 1.5" quat="0.5 0.5 0.5 0.5" size="1.5 1.5 0.01" type="box" conaffinity="0" contype="0" group="1" name="wall_rear_visual" material="walls_mat"/> <geom pos="3 0 1.5" quat="0.5 0.5 -0.5 -0.5" size="3 1.5 0.01" type="box" conaffinity="0" contype="0" group="1" name="wall_front_visual" material="walls_mat"/> --> <!-- Table body --> <body name="table" pos="0 0 0.8"> <geom pos="0 0 0" size="0.6 1.2 0.05" type="box" group="0" name="table_collision" friction="1 0.005 0.0001"/> <geom pos="0 0 0" size="0.6 1.2 0.05" type="box" conaffinity="0" contype="0" group="1" name="table_visual" material="table_ceramic"/> <site pos="0 0 0.025" name="table_top" size="0.001 0.001 0.001" rgba="0 0 0 0"/> <!-- beams (visual only) --> <geom pos=" 0.55 1.15 0.6" size="0.03 0.03 0.6" type="box" conaffinity="0" contype="0" group="1" name="table_beam1_visual" material="table_legs_metal"/> <geom pos=" 0.55 -1.15 0.6" size="0.03 0.03 0.6" type="box" conaffinity="0" contype="0" group="1" name="table_beam2_visual" material="table_legs_metal"/> <geom pos="-0.55 -1.15 0.6" size="0.03 0.03 0.6" type="box" conaffinity="0" contype="0" group="1" name="table_beam3_visual" material="table_legs_metal"/> <geom pos="-0.55 1.15 0.6" size="0.03 0.03 0.6" type="box" conaffinity="0" contype="0" group="1" name="table_beam4_visual" material="table_legs_metal"/> <geom pos=" 0.55 0 1.17" size="0.03 1.12 0.03" type="box" conaffinity="0" contype="0" group="1" name="table_beam5_visual" material="table_legs_metal"/> <geom pos="-0.55 0 1.17" size="0.03 1.12 0.03" type="box" conaffinity="0" contype="0" group="1" name="table_beam6_visual" material="table_legs_metal"/> <geom pos=" 0 -1.15 1.17" size="0.52 0.03 0.03" type="box" conaffinity="0" contype="0" group="1" name="table_beam7_visual" material="table_legs_metal"/> <geom pos=" 0 1.15 1.17" size="0.52 0.03 0.03" type="box" conaffinity="0" contype="0" group="1" name="table_beam8_visual" material="table_legs_metal"/> <geom pos=" 0 0 1.17" size="0.52 0.03 0.03" type="box" conaffinity="0" contype="0" group="1" name="table_beam9_visual" material="table_legs_metal"/> <!-- Legs (visual only) --> <geom pos=" 0.55 1.15 -0.4" size="0.03 0.4" type="cylinder" conaffinity="0" contype="0" group="1" name="table_leg1_visual" material="table_legs_metal"/> <geom pos=" 0.55 -1.15 -0.4" size="0.03 0.4" type="cylinder" conaffinity="0" contype="0" group="1" name="table_leg2_visual" material="table_legs_metal"/> <geom pos="-0.55 -1.15 -0.4" size="0.03 0.4" type="cylinder" conaffinity="0" contype="0" group="1" name="table_leg3_visual" material="table_legs_metal"/> <geom pos="-0.55 1.15 -0.4" size="0.03 0.4" type="cylinder" conaffinity="0" contype="0" group="1" name="table_leg4_visual" material="table_legs_metal"/> <!-- Hook wall (visual only) --> <body name="hook"> <geom pos="0 -0.9 0.25" size="0.03 0.01 0.25" type="box" conaffinity="0" contype="0" group="1" name="bar_with_two_hooks_wall" material="floorplane"/> <geom pos="0 -0.86 0.45" euler="0 0 -90" mesh="bar_with_two_hooks_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="bar_with_two_hooks" group="0" condim="4"/> </body> <!-- Bar wall (visual only) --> <body name="object"> <geom pos="0 0.9 0.25" size="0.03 0.01 0.25" type="box" conaffinity="0" contype="0" group="1" name="two_bars_wall" material="floorplane"/> <geom pos="0 0.84 0.45" euler="0 90 90" mesh="two_bars_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="two_bars" group="0" condim="4"/> </body> <!-- YCB power-drill (visual only) --> <body name="ycb-power-drill"> <geom pos="0 -0.6 0.05" mesh="power-drill_mesh" type="mesh" mass="0.9" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="power-drill" group="0" condim="4"/> </body> <!-- YCB power-drill (visual only) --> <body name="ycb-spatula"> <geom pos="0 -0.3 0.05" mesh="spatula_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="spatula" group="0" condim="4"/> </body> <!-- YCB power-drill (visual only) --> <body name="ycb-adjustable-wrench"> <geom pos="0 -0.2 0.05" mesh="adjustable-wrench_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="adjustable-wrench" group="0" condim="4"/> </body> <!-- YCB power-drill (visual only) --> <body name="ycb-hammer"> <geom pos="0 0 0.05" mesh="hammer_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="hammer" group="0" condim="4"/> </body> <!-- YCB mug (visual only) --> <body name="ycb-mug"> <geom pos="0 0.2 0.05" mesh="mug_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="mug" group="0" condim="4"/> </body> <!-- YCB windex-bottle (visual only) --> <body name="ycb-windex-bottle"> <geom pos="0 0.4 0.05" mesh="windex-bottle_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="windex-bottle" group="0" condim="4"/> </body> <!-- YCB pitcher-base (visual only) --> <body name="ycb-pitcher-base"> <geom pos="0 0.6 0.05" mesh="pitcher-base_mesh" type="mesh" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" material="pitcher-base" group="0" condim="4"/> </body> <!-- My scissor (visual only) --> <body name="my-scissor"> <geom pos="0.09 0.8 0.21" mesh="tt_scissor_mesh" type="mesh" mass="0.9" solimp="0.998 0.998 0.001" solref="0.001 1" density="50" friction="0.95 0.3 0.1" group="0" condim="4"/> </body> </body> <!-- Cam pose (visual only) --> <!-- <geom pos=" 0.55 1.15 1.2" quat="0.1982669 0.1663657 0.6208852 0.7399421" size="0.02 0.1" type="cylinder" conaffinity="0" contype="0" group="1" name="cam1" rgba="0.9 0.9 0.9 1"/> <geom pos=" 0.55 -1.15 1.2" quat="-0.1982669 0.1663657 -0.6208852 0.7399421" size="0.02 0.1" type="cylinder" conaffinity="0" contype="0" group="1" name="cam2" rgba="0.5 0.5 0 1"/> <geom pos=" 0.55 1.15 2" quat=" 0 0 0.6427876 0.7660444" size="0.02 0.1" type="cylinder" conaffinity="0" contype="0" group="1" name="cam3" rgba="0.5 0.5 0 1"/> <geom pos=" 0.55 -1.15 2" quat=" 0 0 0.6427876 0.7660444" size="0.02 0.1" type="cylinder" conaffinity="0" contype="0" group="1" name="cam4" rgba="0.5 0.5 0 1"/> --> <light name="light1" diffuse=".8 .8 .8" dir="0 -.15 -1" directional="false" pos="1 1 4.0" specular="0.3 0.3 0.3" castshadow="false"/> <light name="light2" diffuse=".8 .8 .8" dir="0 -.15 -1" directional="false" pos="-3. -3. 4.0" specular="0.3 0.3 0.3" castshadow="false"/> <!-- front view --> <camera mode="fixed" name="frontview" pos="1.6 0 1.45" quat="0.56 0.43 0.43 0.56" /> <!-- bird view --> <camera mode="fixed" name="birdview" pos="-0.2 0 3.0" quat="0.7071 0 0 0.7071"/> <!-- agent view --> <camera mode="fixed" name="agentview" pos="0.5 0 1.35" quat="0.653 0.271 0.271 0.653"/> <!-- side view --> <camera mode="fixed" name="sideview" pos="-0.05651774593317116 1.2761224129427358 1.4879572214102434" quat="0.009905065491771751 0.006877963156909582 0.5912228352893879 0.806418094001364" /> </worldbody> </mujoco> ``` ::: ## add hang in the env The most important thing is convert the .urdf files into .xml (MJCF format) - reference : https://github.com/wangcongrobot/dual_ur5_husky_mujoco ## other control method ## tactile - see : https://mujoco.readthedocs.io/en/latest/modeling.html - composite objects