#VRML_SIM R2025a utf8 EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2025a/projects/objects/backgrounds/protos/TexturedBackground.proto" EXTERNPROTO "https://raw.githubusercontent.com/cyberbotics/webots/R2025a/projects/objects/backgrounds/protos/TexturedBackgroundLight.proto" WorldInfo { basicTimeStep 16 } Viewpoint { orientation -0.25635520317819327 -0.11512688037582759 0.95970193873848 3.9554765517228683 position 1.7243922962992353 1.7163795653296472 1.55302324506386 } TexturedBackground { } TexturedBackgroundLight { } Solid { translation 0.15 0 0.25 children [ Shape { appearance Appearance { texture ImageTexture { url [ "../texture/whiteboard.jpg" ] } } geometry Box { size 1.4 1.7 0.01 } } ] name "table-paintable" } Robot { rotation 0 0 1 -1.58 children [ DEF GEOMETRY_0 Group { children [ DEF A0 Shape { appearance PBRAppearance { baseColor 1 0.333333 0 roughness 1 metalness 0 } geometry Mesh { url [ "../meshes/base-1.stl" ] } } DEF B0 Shape { appearance DEF WHITE PBRAppearance { roughness 1 metalness 0 } geometry Mesh { url [ "../meshes/base-2.stl" ] } } ] } HingeJoint { jointParameters HingeJointParameters { axis 0 0 1 anchor 0 0 0.5925 minStop -1.845 maxStop 1.845 } device [ PositionSensor { name "joint_1_sensor" } RotationalMotor { name "joint_1" maxVelocity 2 maxTorque 100 } ] endPoint Solid { translation 0 0 0.5925 rotation 0 0 1 1.5799999999999947 children [ DEF LINK1_SHAPE Shape { appearance USE WHITE geometry Mesh { url [ "../meshes/brazo.stl" ] } } HingeJoint { jointParameters HingeJointParameters { axis 0 0 1 anchor 0.4025 0 0 minStop -2.574 maxStop 2.574 } device [ PositionSensor { name "joint_2_sensor" } RotationalMotor { name "joint_2" maxVelocity 2 minPosition -2.574 maxPosition 2.574 } ] endPoint Solid { translation 0.4025 0 0 children [ DEF A2 Shape { appearance USE WHITE geometry Mesh { url [ "../meshes/antebrazo-1.stl" ] } } DEF B2 Shape { appearance DEF DARK_GRAY PBRAppearance { baseColor 0.4 0.4 0.4 roughness 1 metalness 0 } geometry Mesh { url [ "../meshes/antebrazo-2.stl" ] } } SliderJoint { jointParameters JointParameters { } device [ PositionSensor { name "joint_3_sensor" } LinearMotor { name "joint_3" } ] endPoint Solid { translation 0.37763 0 0.17023100000000002 children [ DEF GEOMETRY_3 Shape { appearance USE DARK_GRAY geometry Mesh { url [ "../meshes/mano.stl" ] } } HingeJoint { jointParameters HingeJointParameters { axis 0 0 1 } device [ PositionSensor { name "joint_4_sensor" } RotationalMotor { name "joint_4" } ] endPoint Solid { children [ DEF GEOMETRY_4 Shape { appearance PBRAppearance { baseColor 0.6 0.6 0.6 roughness 1 metalness 0 } geometry Mesh { url [ "../meshes/dedo.stl" ] } } DEF TCP Pose { translation 0 0 -0.407 children [ Shape { appearance PBRAppearance { baseColor 1 0.666667 0 roughness 1 metalness 0 } geometry Cylinder { height 0.002 radius 0.002 } } Pen { translation 0 0 -0.002 rotation 1 0 0 0 inkDensity 1 leadSize 0.01 maxDistance 0.005 } ] } ] name "link_4" boundingObject USE GEOMETRY_4 physics Physics { } } } ] name "link_3" boundingObject USE GEOMETRY_3 physics Physics { } } } ] name "link_2" boundingObject Shape { geometry Mesh { url [ "../meshes/antebrazo.stl" ] } } physics Physics { } } } ] name "link_1" boundingObject USE LINK1_SHAPE physics Physics { } } } ] boundingObject DEF GEOMETRY_0 Group { children [ DEF A0 Shape { appearance PBRAppearance { baseColor 1 0.333333 0 roughness 1 metalness 0 } geometry Mesh { url [ "../meshes/base-1.stl" ] } } DEF B0 Shape { appearance DEF WHITE PBRAppearance { roughness 1 metalness 0 } geometry Mesh { url [ "../meshes/base-2.stl" ] } } ] } controller "" supervisor TRUE }