mirror of
https://github.com/PotentiaRobotics/engine-software.git
synced 2025-04-16 02:00:16 -04:00
135 lines
2.7 KiB
Plaintext
135 lines
2.7 KiB
Plaintext
#VRML_SIM R2021a utf8
|
|
WorldInfo {
|
|
coordinateSystem "NUE"
|
|
}
|
|
Viewpoint {
|
|
orientation -0.7241113403564003 0.6708542148873753 0.16005433182235554 0.3286771770738909
|
|
position 0.9187932527597619 1.807787251982618 3.3212186235849788
|
|
}
|
|
TexturedBackground {
|
|
}
|
|
TexturedBackgroundLight {
|
|
}
|
|
RectangleArena {
|
|
floorSize 5 5
|
|
}
|
|
Robot {
|
|
translation 0 0.03 0
|
|
children [
|
|
DEF Body Transform {
|
|
translation 0 1.3 0
|
|
children [
|
|
Shape {
|
|
appearance PBRAppearance {
|
|
roughness 1
|
|
metalness 0
|
|
}
|
|
geometry Box {
|
|
size 0.5 0.7 0.25
|
|
}
|
|
}
|
|
]
|
|
}
|
|
BallJoint {
|
|
jointParameters BallJointParameters {
|
|
anchor 0 1.775 0
|
|
}
|
|
jointParameters2 JointParameters {
|
|
axis 1 0 0
|
|
}
|
|
jointParameters3 JointParameters {
|
|
}
|
|
device [
|
|
RotationalMotor {
|
|
name "neck_pitch"
|
|
}
|
|
]
|
|
device2 [
|
|
RotationalMotor {
|
|
name "neck_yaw"
|
|
minPosition -1.5707963267948966
|
|
maxPosition 1.5707963267948966
|
|
}
|
|
]
|
|
device3 [
|
|
RotationalMotor {
|
|
name "neck_roll"
|
|
}
|
|
]
|
|
endPoint Solid {
|
|
translation 0 1.775 0
|
|
children [
|
|
DEF head Shape {
|
|
appearance PBRAppearance {
|
|
roughness 1
|
|
metalness 0
|
|
}
|
|
geometry Sphere {
|
|
radius 0.125
|
|
}
|
|
}
|
|
]
|
|
name "solid(2)"
|
|
boundingObject USE head
|
|
physics Physics {
|
|
}
|
|
}
|
|
}
|
|
HingeJoint {
|
|
jointParameters HingeJointParameters {
|
|
anchor -0.25 1.55 0
|
|
}
|
|
device [
|
|
RotationalMotor {
|
|
name "arm_pitch"
|
|
}
|
|
]
|
|
endPoint Solid {
|
|
translation -0.25 1.55 0
|
|
rotation 0 0 1 1.57
|
|
children [
|
|
DEF arm_joint Shape {
|
|
appearance PBRAppearance {
|
|
roughness 1
|
|
metalness 0
|
|
}
|
|
geometry Cylinder {
|
|
height 0.1
|
|
radius 0.075
|
|
}
|
|
}
|
|
]
|
|
boundingObject USE arm_joint
|
|
physics Physics {
|
|
}
|
|
}
|
|
}
|
|
HingeJoint {
|
|
jointParameters HingeJointParameters {
|
|
axis 0 0 1
|
|
anchor -0.375 1.55 0
|
|
}
|
|
device [
|
|
RotationalMotor {
|
|
name "arm_yaw"
|
|
}
|
|
]
|
|
endPoint Solid {
|
|
translation -0.375 1.55 0
|
|
rotation 1 0 0 1.57
|
|
children [
|
|
USE arm_joint
|
|
]
|
|
name "solid(1)"
|
|
boundingObject USE arm_joint
|
|
physics Physics {
|
|
}
|
|
}
|
|
}
|
|
]
|
|
boundingObject USE Body
|
|
physics Physics {
|
|
}
|
|
controller "olympian"
|
|
}
|