Add UR5e robot support with inverse kinematics and environment setup
Browse files- Introduced a new UR5e robot model with 6 degrees of freedom and a Robotiq 2F-85 gripper.
- Implemented an inverse kinematics controller for the UR5e to compute joint positions based on target poses.
- Created a new Gymnasium environment for the UR5e, enabling simulation and control.
- Updated README.md to include UR5e specifications, control modes, and example JSON state data.
- Added various model assets and configurations for the UR5e robot, enhancing simulation capabilities.
- README.md +91 -11
- mujoco_server.py +353 -52
- robots/ur5/controllers/ik_controller.py +161 -0
- robots/ur5/model/assets/base.stl +3 -0
- robots/ur5/model/assets/base_0.obj +0 -0
- robots/ur5/model/assets/base_1.obj +0 -0
- robots/ur5/model/assets/base_mount.stl +3 -0
- robots/ur5/model/assets/coupler.stl +3 -0
- robots/ur5/model/assets/driver.stl +3 -0
- robots/ur5/model/assets/follower.stl +3 -0
- robots/ur5/model/assets/forearm_0.obj +0 -0
- robots/ur5/model/assets/forearm_1.obj +2159 -0
- robots/ur5/model/assets/forearm_2.obj +0 -0
- robots/ur5/model/assets/forearm_3.obj +0 -0
- robots/ur5/model/assets/pad.stl +3 -0
- robots/ur5/model/assets/shoulder_0.obj +0 -0
- robots/ur5/model/assets/shoulder_1.obj +0 -0
- robots/ur5/model/assets/shoulder_2.obj +0 -0
- robots/ur5/model/assets/silicone_pad.stl +3 -0
- robots/ur5/model/assets/spring_link.stl +3 -0
- robots/ur5/model/assets/upperarm_0.obj +0 -0
- robots/ur5/model/assets/upperarm_1.obj +0 -0
- robots/ur5/model/assets/upperarm_2.obj +0 -0
- robots/ur5/model/assets/upperarm_3.obj +0 -0
- robots/ur5/model/assets/wrist1_0.obj +0 -0
- robots/ur5/model/assets/wrist1_1.obj +0 -0
- robots/ur5/model/assets/wrist1_2.obj +0 -0
- robots/ur5/model/assets/wrist2_0.obj +0 -0
- robots/ur5/model/assets/wrist2_1.obj +0 -0
- robots/ur5/model/assets/wrist2_2.obj +0 -0
- robots/ur5/model/assets/wrist3.obj +0 -0
- robots/ur5/model/scene.xml +340 -0
- robots/ur5/ur5_env.py +302 -0
README.md
CHANGED
|
@@ -16,6 +16,14 @@ A unified MuJoCo-based robot simulation platform with web interface for multiple
|
|
| 16 |
- **PyMPC Gait**: Uses Quadruped-PyMPC gait generator (requires extra dependencies)
|
| 17 |
- **Trot Gait**: Simple open-loop trot pattern
|
| 18 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 19 |
## Features
|
| 20 |
|
| 21 |
- Real-time MuJoCo physics simulation
|
|
@@ -142,16 +150,25 @@ docker run --gpus all -p 3004:3004 \
|
|
| 142 |
|
| 143 |
## Controls
|
| 144 |
|
|
|
|
| 145 |
- **W / Arrow Up**: Walk forward
|
| 146 |
- **S / Arrow Down**: Walk backward
|
| 147 |
- **A / Arrow Left**: Turn left
|
| 148 |
- **D / Arrow Right**: Turn right
|
| 149 |
- **Q**: Strafe left
|
| 150 |
- **E**: Strafe right
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 151 |
- **Mouse drag**: Rotate camera
|
| 152 |
- **Scroll wheel**: Zoom camera
|
| 153 |
-
- **Robot selector**: Switch between G1 and
|
| 154 |
-
- **Reset button**: Reset robot to
|
| 155 |
|
| 156 |
## Architecture
|
| 157 |
|
|
@@ -177,7 +194,7 @@ docker run --gpus all -p 3004:3004 \
|
|
| 177 |
│ ▼ ▼ │
|
| 178 |
│ ┌───────────────────────────────────┐ │
|
| 179 |
│ │ Active Environment (env) │ │
|
| 180 |
-
│ │
|
| 181 |
│ └───────────────────────────────────┘ │
|
| 182 |
└─────────────────────────────────────────────────────────────────────────┘
|
| 183 |
│
|
|
@@ -204,6 +221,18 @@ docker run --gpus all -p 3004:3004 \
|
|
| 204 |
│ └────────────────────────────┘ │ - 4 legs × 3 joints │ │
|
| 205 |
│ │ - Gait-based locomotion │ │
|
| 206 |
│ └────────────────────────────┘ │
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 207 |
└─────────────────────────────────────────────────────────────────────────┘
|
| 208 |
│
|
| 209 |
│ mujoco.mj_step()
|
|
@@ -259,14 +288,21 @@ nova_sim/
|
|
| 259 |
│ │ ├── rl_policy.py # RL walking policy
|
| 260 |
│ │ ├── pd_standing.py # Standing controller
|
| 261 |
│ │ └── keyframe.py # Keyframe controller
|
| 262 |
-
│
|
| 263 |
-
│
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 264 |
│ ├── model/ # MuJoCo model files
|
| 265 |
-
│
|
| 266 |
-
│
|
| 267 |
-
│
|
| 268 |
-
│
|
| 269 |
-
│ └── pd_standing.py # Standing controller
|
| 270 |
└── README.md
|
| 271 |
```
|
| 272 |
|
|
@@ -339,7 +375,7 @@ All messages are JSON with `{type, data}` structure:
|
|
| 339 |
```json
|
| 340 |
{"type": "switch_robot", "data": {"robot": "spot"}}
|
| 341 |
```
|
| 342 |
-
- `robot`: `"g1"` or `"
|
| 343 |
|
| 344 |
**`camera`:**
|
| 345 |
```json
|
|
@@ -361,9 +397,37 @@ All messages are JSON with `{type, data}` structure:
|
|
| 361 |
{"type": "camera_follow", "data": {"follow": true}}
|
| 362 |
```
|
| 363 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 364 |
#### Server → Client Messages
|
| 365 |
|
| 366 |
**`state`** (broadcast at ~10 Hz):
|
|
|
|
|
|
|
| 367 |
```json
|
| 368 |
{
|
| 369 |
"type": "state",
|
|
@@ -379,6 +443,22 @@ All messages are JSON with `{type, data}` structure:
|
|
| 379 |
}
|
| 380 |
```
|
| 381 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 382 |
### HTTP Endpoints
|
| 383 |
|
| 384 |
| Endpoint | Method | Description |
|
|
|
|
| 16 |
- **PyMPC Gait**: Uses Quadruped-PyMPC gait generator (requires extra dependencies)
|
| 17 |
- **Trot Gait**: Simple open-loop trot pattern
|
| 18 |
|
| 19 |
+
### Universal Robots UR5e (Robot Arm)
|
| 20 |
+
- 6 degrees of freedom (6-axis industrial arm)
|
| 21 |
+
- Robotiq 2F-85 gripper
|
| 22 |
+
- Two control modes:
|
| 23 |
+
- **IK Mode**: Set target XYZ position, inverse kinematics computes joint angles
|
| 24 |
+
- **Joint Mode**: Direct control of individual joint positions
|
| 25 |
+
- End-effector position and orientation tracking
|
| 26 |
+
|
| 27 |
## Features
|
| 28 |
|
| 29 |
- Real-time MuJoCo physics simulation
|
|
|
|
| 150 |
|
| 151 |
## Controls
|
| 152 |
|
| 153 |
+
### Locomotion Robots (G1, Spot)
|
| 154 |
- **W / Arrow Up**: Walk forward
|
| 155 |
- **S / Arrow Down**: Walk backward
|
| 156 |
- **A / Arrow Left**: Turn left
|
| 157 |
- **D / Arrow Right**: Turn right
|
| 158 |
- **Q**: Strafe left
|
| 159 |
- **E**: Strafe right
|
| 160 |
+
|
| 161 |
+
### Robot Arm (UR5)
|
| 162 |
+
- **IK Mode**: Use XYZ sliders to set end-effector target position
|
| 163 |
+
- **Joint Mode**: Use J1-J6 sliders to control individual joints
|
| 164 |
+
- **Gripper**: Open/Close buttons for Robotiq gripper
|
| 165 |
+
- **Home**: Return to home position (joint mode)
|
| 166 |
+
|
| 167 |
+
### Common Controls
|
| 168 |
- **Mouse drag**: Rotate camera
|
| 169 |
- **Scroll wheel**: Zoom camera
|
| 170 |
+
- **Robot selector**: Switch between G1, Spot, and UR5
|
| 171 |
+
- **Reset button**: Reset robot to default pose
|
| 172 |
|
| 173 |
## Architecture
|
| 174 |
|
|
|
|
| 194 |
│ ▼ ▼ │
|
| 195 |
│ ┌───────────────────────────────────┐ │
|
| 196 |
│ │ Active Environment (env) │ │
|
| 197 |
+
│ │ G1Env, SpotEnv, or UR5Env (Gym) │ │
|
| 198 |
│ └───────────────────────────────────┘ │
|
| 199 |
└─────────────────────────────────────────────────────────────────────────┘
|
| 200 |
│
|
|
|
|
| 221 |
│ └────────────────────────────┘ │ - 4 legs × 3 joints │ │
|
| 222 |
│ │ - Gait-based locomotion │ │
|
| 223 |
│ └────────────────────────────┘ │
|
| 224 |
+
│ │
|
| 225 |
+
│ ┌────────────────────────────┐ │
|
| 226 |
+
│ │ UR5Env │ 6 DOF Robot Arm │
|
| 227 |
+
│ │ ┌──────────────────────┐ │ - IK or direct joint control │
|
| 228 |
+
│ │ │ scene.xml (UR5e + │ │ - Robotiq 2F-85 gripper │
|
| 229 |
+
│ │ │ Robotiq 2F-85) │ │ - End-effector tracking │
|
| 230 |
+
│ │ └──────────────────────┘ │ │
|
| 231 |
+
│ │ ┌──────────────────────┐ │ │
|
| 232 |
+
│ │ │ ik_controller.py │ │ │
|
| 233 |
+
│ │ │ (Damped LS IK) │ │ │
|
| 234 |
+
│ │ └──────────────────────┘ │ │
|
| 235 |
+
│ └────────────────────────────┘ │
|
| 236 |
└─────────────────────────────────────────────────────────────────────────┘
|
| 237 |
│
|
| 238 |
│ mujoco.mj_step()
|
|
|
|
| 288 |
│ │ ├── rl_policy.py # RL walking policy
|
| 289 |
│ │ ├── pd_standing.py # Standing controller
|
| 290 |
│ │ └── keyframe.py # Keyframe controller
|
| 291 |
+
│ ├── spot/ # Boston Dynamics Spot quadruped
|
| 292 |
+
│ │ ├── spot_env.py # Gymnasium environment
|
| 293 |
+
│ │ ├── model/ # MuJoCo model files
|
| 294 |
+
│ │ └── controllers/ # Spot controllers
|
| 295 |
+
│ │ ├── mpc_gait.py # MPC-inspired gait (default)
|
| 296 |
+
│ │ ├── quadruped_pympc_controller.py # PyMPC gait
|
| 297 |
+
│ │ ├── trot_gait.py # Simple trot gait
|
| 298 |
+
│ │ └── pd_standing.py # Standing controller
|
| 299 |
+
│ └── ur5/ # Universal Robots UR5e arm
|
| 300 |
+
│ ├── ur5_env.py # Gymnasium environment
|
| 301 |
│ ├── model/ # MuJoCo model files
|
| 302 |
+
│ │ ├── scene.xml # Combined UR5e + Robotiq scene
|
| 303 |
+
│ │ └── assets/ # Mesh files
|
| 304 |
+
│ └── controllers/
|
| 305 |
+
│ └── ik_controller.py # Damped least-squares IK
|
|
|
|
| 306 |
└── README.md
|
| 307 |
```
|
| 308 |
|
|
|
|
| 375 |
```json
|
| 376 |
{"type": "switch_robot", "data": {"robot": "spot"}}
|
| 377 |
```
|
| 378 |
+
- `robot`: `"g1"`, `"spot"`, or `"ur5"`
|
| 379 |
|
| 380 |
**`camera`:**
|
| 381 |
```json
|
|
|
|
| 397 |
{"type": "camera_follow", "data": {"follow": true}}
|
| 398 |
```
|
| 399 |
|
| 400 |
+
#### UR5-Specific Messages
|
| 401 |
+
|
| 402 |
+
**`arm_target`** (IK mode - set end-effector target):
|
| 403 |
+
```json
|
| 404 |
+
{"type": "arm_target", "data": {"x": 0.4, "y": 0.0, "z": 0.6}}
|
| 405 |
+
```
|
| 406 |
+
- `x`, `y`, `z`: Target position in meters
|
| 407 |
+
|
| 408 |
+
**`joint_positions`** (Joint mode - direct joint control):
|
| 409 |
+
```json
|
| 410 |
+
{"type": "joint_positions", "data": {"positions": [-1.57, -1.57, 1.57, -1.57, -1.57, 0.0]}}
|
| 411 |
+
```
|
| 412 |
+
- `positions`: Array of 6 joint angles in radians [J1, J2, J3, J4, J5, J6]
|
| 413 |
+
|
| 414 |
+
**`control_mode`** (Switch control mode):
|
| 415 |
+
```json
|
| 416 |
+
{"type": "control_mode", "data": {"mode": "ik"}}
|
| 417 |
+
```
|
| 418 |
+
- `mode`: `"ik"` (end-effector target) or `"joint"` (direct joint positions)
|
| 419 |
+
|
| 420 |
+
**`gripper`** (Control gripper):
|
| 421 |
+
```json
|
| 422 |
+
{"type": "gripper", "data": {"action": "close"}}
|
| 423 |
+
```
|
| 424 |
+
- `action`: `"open"` or `"close"`
|
| 425 |
+
|
| 426 |
#### Server → Client Messages
|
| 427 |
|
| 428 |
**`state`** (broadcast at ~10 Hz):
|
| 429 |
+
|
| 430 |
+
For locomotion robots (G1, Spot):
|
| 431 |
```json
|
| 432 |
{
|
| 433 |
"type": "state",
|
|
|
|
| 443 |
}
|
| 444 |
```
|
| 445 |
|
| 446 |
+
For robot arm (UR5):
|
| 447 |
+
```json
|
| 448 |
+
{
|
| 449 |
+
"type": "state",
|
| 450 |
+
"data": {
|
| 451 |
+
"robot": "ur5",
|
| 452 |
+
"end_effector": {"x": 0.4, "y": 0.0, "z": 0.6},
|
| 453 |
+
"target": {"x": 0.4, "y": 0.0, "z": 0.6},
|
| 454 |
+
"gripper": 128,
|
| 455 |
+
"joint_positions": [-1.57, -1.57, 1.57, -1.57, -1.57, 0.0],
|
| 456 |
+
"control_mode": "ik",
|
| 457 |
+
"steps": 1234
|
| 458 |
+
}
|
| 459 |
+
}
|
| 460 |
+
```
|
| 461 |
+
|
| 462 |
### HTTP Endpoints
|
| 463 |
|
| 464 |
| Endpoint | Method | Description |
|
mujoco_server.py
CHANGED
|
@@ -43,11 +43,12 @@ TARGET_FPS = int(os.environ.get('TARGET_FPS', 30 if IN_DOCKER else 60))
|
|
| 43 |
SIM_STEPS_PER_FRAME = int(os.environ.get('SIM_STEPS_PER_FRAME', 10 if IN_DOCKER else 5))
|
| 44 |
|
| 45 |
# Current robot type
|
| 46 |
-
current_robot = "g1" #
|
| 47 |
|
| 48 |
# Environment instances (lazy loaded)
|
| 49 |
env_g1 = None
|
| 50 |
env_spot = None
|
|
|
|
| 51 |
env = None # Active environment
|
| 52 |
|
| 53 |
# Simulation state
|
|
@@ -97,6 +98,20 @@ def init_spot():
|
|
| 97 |
return env_spot
|
| 98 |
|
| 99 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 100 |
def switch_robot(robot_type):
|
| 101 |
"""Switch to a different robot."""
|
| 102 |
global env, current_robot, renderer, cam
|
|
@@ -119,6 +134,12 @@ def switch_robot(robot_type):
|
|
| 119 |
env = init_spot()
|
| 120 |
cam.lookat = np.array([0, 0, 0.4])
|
| 121 |
cam.distance = 2.5
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 122 |
else:
|
| 123 |
print(f"Unknown robot type: {robot_type}")
|
| 124 |
return
|
|
@@ -144,22 +165,43 @@ def broadcast_state():
|
|
| 144 |
cmd = env.get_command()
|
| 145 |
steps = env.steps
|
| 146 |
|
| 147 |
-
|
| 148 |
-
|
| 149 |
-
|
| 150 |
-
|
| 151 |
-
|
| 152 |
-
|
| 153 |
-
|
| 154 |
-
|
| 155 |
-
|
| 156 |
-
|
| 157 |
-
|
| 158 |
-
|
| 159 |
-
|
| 160 |
-
|
| 161 |
-
|
| 162 |
-
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 163 |
|
| 164 |
# Send to all connected clients
|
| 165 |
with ws_clients_lock:
|
|
@@ -204,8 +246,8 @@ def simulation_loop():
|
|
| 204 |
for _ in range(physics_steps_per_frame):
|
| 205 |
env.step_with_controller(dt=sim_dt)
|
| 206 |
|
| 207 |
-
# Update camera to follow robot
|
| 208 |
-
if camera_follow:
|
| 209 |
robot_pos = env.data.qpos[:3]
|
| 210 |
cam.lookat[0] = robot_pos[0]
|
| 211 |
cam.lookat[1] = robot_pos[1]
|
|
@@ -284,6 +326,11 @@ def handle_ws_message(data):
|
|
| 284 |
if current_robot == "g1":
|
| 285 |
cam.distance = 3.0
|
| 286 |
cam.lookat = np.array([0.0, 0.0, 0.8])
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 287 |
else:
|
| 288 |
cam.distance = 2.5
|
| 289 |
cam.lookat = np.array([0.0, 0.0, 0.4])
|
|
@@ -319,6 +366,44 @@ def handle_ws_message(data):
|
|
| 319 |
payload = data.get('data', {})
|
| 320 |
camera_follow = payload.get('follow', True)
|
| 321 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 322 |
|
| 323 |
@sock.route(f'{API_PREFIX}/ws')
|
| 324 |
def websocket_handler(ws):
|
|
@@ -350,17 +435,24 @@ def websocket_handler(ws):
|
|
| 350 |
print('WebSocket client disconnected')
|
| 351 |
|
| 352 |
|
| 353 |
-
#
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 354 |
@app.route('/')
|
| 355 |
def root_redirect():
|
| 356 |
return render_template_string("""
|
| 357 |
<!DOCTYPE html>
|
| 358 |
<html>
|
| 359 |
<head>
|
| 360 |
-
<meta http-equiv="refresh" content="0; url='
|
| 361 |
</head>
|
| 362 |
<body>
|
| 363 |
-
<p>Redirecting to <a href=
|
| 364 |
</body>
|
| 365 |
</html>
|
| 366 |
""")
|
|
@@ -455,6 +547,29 @@ def index():
|
|
| 455 |
margin-top: 10px;
|
| 456 |
font-size: 0.8em;
|
| 457 |
}
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 458 |
</style>
|
| 459 |
</head>
|
| 460 |
<body>
|
|
@@ -472,43 +587,138 @@ def index():
|
|
| 472 |
<select id="robot_select" onchange="switchRobot()">
|
| 473 |
<option value="g1">Unitree G1 (Humanoid)</option>
|
| 474 |
<option value="spot">Boston Dynamics Spot (Quadruped)</option>
|
|
|
|
| 475 |
</select>
|
| 476 |
<div class="robot-info" id="robot_info">
|
| 477 |
29 DOF humanoid with RL walking policy
|
| 478 |
</div>
|
| 479 |
</div>
|
| 480 |
|
| 481 |
-
<
|
| 482 |
-
|
| 483 |
-
<div class="
|
| 484 |
-
<
|
| 485 |
-
|
| 486 |
-
|
| 487 |
-
|
| 488 |
-
<
|
| 489 |
-
<
|
| 490 |
-
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 491 |
</div>
|
| 492 |
-
<div class="
|
| 493 |
-
|
| 494 |
-
<button class="rl-btn stop" onclick="setCmd(0, 0, 0)">Stop</button>
|
| 495 |
-
<button class="rl-btn" onmousedown="setCmd(0, -0.4, 0)" onmouseup="setCmd(0,0,0)" ontouchstart="setCmd(0, -0.4, 0)" ontouchend="setCmd(0,0,0)">E Strafe R</button>
|
| 496 |
</div>
|
| 497 |
</div>
|
| 498 |
-
|
| 499 |
-
|
|
|
|
|
|
|
|
|
|
|
|
|
| 500 |
</div>
|
| 501 |
</div>
|
| 502 |
|
| 503 |
-
<
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 504 |
|
| 505 |
-
|
| 506 |
-
<
|
| 507 |
-
|
| 508 |
-
|
| 509 |
-
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 510 |
</div>
|
| 511 |
|
|
|
|
|
|
|
| 512 |
<div class="camera-controls">
|
| 513 |
<div class="control-group">
|
| 514 |
<label>Camera Distance</label>
|
|
@@ -545,14 +755,19 @@ def index():
|
|
| 545 |
|
| 546 |
const robotInfoText = {
|
| 547 |
'g1': '29 DOF humanoid with RL walking policy',
|
| 548 |
-
'spot': '12 DOF quadruped with trot gait controller'
|
|
|
|
| 549 |
};
|
| 550 |
|
| 551 |
const robotTitles = {
|
| 552 |
'g1': 'Unitree G1 Humanoid',
|
| 553 |
-
'spot': 'Boston Dynamics Spot'
|
|
|
|
| 554 |
};
|
| 555 |
|
|
|
|
|
|
|
|
|
|
| 556 |
function connect() {
|
| 557 |
ws = new WebSocket(WS_URL);
|
| 558 |
|
|
@@ -587,12 +802,41 @@ def index():
|
|
| 587 |
const msg = JSON.parse(event.data);
|
| 588 |
if (msg.type === 'state') {
|
| 589 |
const data = msg.data;
|
| 590 |
-
|
| 591 |
-
|
| 592 |
-
|
| 593 |
-
|
| 594 |
-
|
| 595 |
-
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 596 |
|
| 597 |
if (data.robot && robotSelect.value !== data.robot) {
|
| 598 |
robotSelect.value = data.robot;
|
|
@@ -614,6 +858,15 @@ def index():
|
|
| 614 |
function updateRobotUI(robot) {
|
| 615 |
robotTitle.innerText = robotTitles[robot] || robot;
|
| 616 |
robotInfo.innerText = robotInfoText[robot] || '';
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 617 |
}
|
| 618 |
|
| 619 |
function switchRobot() {
|
|
@@ -647,6 +900,54 @@ def index():
|
|
| 647 |
send('camera_follow', {follow});
|
| 648 |
}
|
| 649 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 650 |
function updateCmdFromKeys() {
|
| 651 |
let vx = 0, vy = 0, vyaw = 0;
|
| 652 |
if (keysPressed.has('KeyW') || keysPressed.has('ArrowUp')) vx = 0.8;
|
|
|
|
| 43 |
SIM_STEPS_PER_FRAME = int(os.environ.get('SIM_STEPS_PER_FRAME', 10 if IN_DOCKER else 5))
|
| 44 |
|
| 45 |
# Current robot type
|
| 46 |
+
current_robot = "g1" # "g1", "spot", or "ur5"
|
| 47 |
|
| 48 |
# Environment instances (lazy loaded)
|
| 49 |
env_g1 = None
|
| 50 |
env_spot = None
|
| 51 |
+
env_ur5 = None
|
| 52 |
env = None # Active environment
|
| 53 |
|
| 54 |
# Simulation state
|
|
|
|
| 98 |
return env_spot
|
| 99 |
|
| 100 |
|
| 101 |
+
def init_ur5():
|
| 102 |
+
"""Initialize UR5e environment."""
|
| 103 |
+
global env_ur5
|
| 104 |
+
if env_ur5 is None:
|
| 105 |
+
# Import UR5Env from robots/ur5 directory
|
| 106 |
+
ur5_dir = os.path.join(_nova_sim_dir, 'robots', 'ur5')
|
| 107 |
+
sys.path.insert(0, ur5_dir)
|
| 108 |
+
from ur5_env import UR5Env
|
| 109 |
+
sys.path.pop(0)
|
| 110 |
+
env_ur5 = UR5Env(render_mode="rgb_array", width=RENDER_WIDTH, height=RENDER_HEIGHT)
|
| 111 |
+
env_ur5.reset()
|
| 112 |
+
return env_ur5
|
| 113 |
+
|
| 114 |
+
|
| 115 |
def switch_robot(robot_type):
|
| 116 |
"""Switch to a different robot."""
|
| 117 |
global env, current_robot, renderer, cam
|
|
|
|
| 134 |
env = init_spot()
|
| 135 |
cam.lookat = np.array([0, 0, 0.4])
|
| 136 |
cam.distance = 2.5
|
| 137 |
+
elif robot_type == "ur5":
|
| 138 |
+
env = init_ur5()
|
| 139 |
+
cam.lookat = np.array([0.3, 0, 0.6])
|
| 140 |
+
cam.distance = 1.8
|
| 141 |
+
cam.azimuth = 150
|
| 142 |
+
cam.elevation = -25
|
| 143 |
else:
|
| 144 |
print(f"Unknown robot type: {robot_type}")
|
| 145 |
return
|
|
|
|
| 165 |
cmd = env.get_command()
|
| 166 |
steps = env.steps
|
| 167 |
|
| 168 |
+
# UR5 has different state structure
|
| 169 |
+
if current_robot == "ur5":
|
| 170 |
+
ee_pos = env.get_end_effector_pos()
|
| 171 |
+
target = env.get_target()
|
| 172 |
+
gripper = env.get_gripper()
|
| 173 |
+
joint_pos = env.get_joint_positions()
|
| 174 |
+
control_mode = env.get_control_mode()
|
| 175 |
+
|
| 176 |
+
state_msg = json.dumps({
|
| 177 |
+
'type': 'state',
|
| 178 |
+
'data': {
|
| 179 |
+
'robot': current_robot,
|
| 180 |
+
'end_effector': {'x': float(ee_pos[0]), 'y': float(ee_pos[1]), 'z': float(ee_pos[2])},
|
| 181 |
+
'target': {'x': float(target[0]), 'y': float(target[1]), 'z': float(target[2])},
|
| 182 |
+
'gripper': float(gripper),
|
| 183 |
+
'joint_positions': [float(j) for j in joint_pos],
|
| 184 |
+
'control_mode': control_mode,
|
| 185 |
+
'steps': int(steps)
|
| 186 |
+
}
|
| 187 |
+
})
|
| 188 |
+
else:
|
| 189 |
+
base_height = float(obs[2])
|
| 190 |
+
base_quat = obs[3:7]
|
| 191 |
+
upright = float(base_quat[0] ** 2)
|
| 192 |
+
|
| 193 |
+
state_msg = json.dumps({
|
| 194 |
+
'type': 'state',
|
| 195 |
+
'data': {
|
| 196 |
+
'robot': current_robot,
|
| 197 |
+
'base_height': base_height,
|
| 198 |
+
'upright': upright,
|
| 199 |
+
'steps': int(steps),
|
| 200 |
+
'vx': float(cmd[0]),
|
| 201 |
+
'vy': float(cmd[1]),
|
| 202 |
+
'vyaw': float(cmd[2])
|
| 203 |
+
}
|
| 204 |
+
})
|
| 205 |
|
| 206 |
# Send to all connected clients
|
| 207 |
with ws_clients_lock:
|
|
|
|
| 246 |
for _ in range(physics_steps_per_frame):
|
| 247 |
env.step_with_controller(dt=sim_dt)
|
| 248 |
|
| 249 |
+
# Update camera to follow robot (not for UR5 which is stationary)
|
| 250 |
+
if camera_follow and current_robot != "ur5":
|
| 251 |
robot_pos = env.data.qpos[:3]
|
| 252 |
cam.lookat[0] = robot_pos[0]
|
| 253 |
cam.lookat[1] = robot_pos[1]
|
|
|
|
| 326 |
if current_robot == "g1":
|
| 327 |
cam.distance = 3.0
|
| 328 |
cam.lookat = np.array([0.0, 0.0, 0.8])
|
| 329 |
+
elif current_robot == "ur5":
|
| 330 |
+
cam.distance = 1.8
|
| 331 |
+
cam.lookat = np.array([0.3, 0.0, 0.6])
|
| 332 |
+
cam.azimuth = 150
|
| 333 |
+
cam.elevation = -25
|
| 334 |
else:
|
| 335 |
cam.distance = 2.5
|
| 336 |
cam.lookat = np.array([0.0, 0.0, 0.4])
|
|
|
|
| 366 |
payload = data.get('data', {})
|
| 367 |
camera_follow = payload.get('follow', True)
|
| 368 |
|
| 369 |
+
# UR5-specific messages
|
| 370 |
+
elif msg_type == 'arm_target':
|
| 371 |
+
payload = data.get('data', {})
|
| 372 |
+
x = payload.get('x', 0.4)
|
| 373 |
+
y = payload.get('y', 0.0)
|
| 374 |
+
z = payload.get('z', 0.6)
|
| 375 |
+
with mujoco_lock:
|
| 376 |
+
if env is not None and current_robot == "ur5":
|
| 377 |
+
env.set_target(x, y, z)
|
| 378 |
+
|
| 379 |
+
elif msg_type == 'gripper':
|
| 380 |
+
payload = data.get('data', {})
|
| 381 |
+
action = payload.get('action', 'open')
|
| 382 |
+
if action == 'open':
|
| 383 |
+
value = 0 # 0 = open
|
| 384 |
+
elif action == 'close':
|
| 385 |
+
value = 255 # 255 = closed
|
| 386 |
+
else:
|
| 387 |
+
value = payload.get('value', 128)
|
| 388 |
+
with mujoco_lock:
|
| 389 |
+
if env is not None and current_robot == "ur5":
|
| 390 |
+
env.set_gripper(value)
|
| 391 |
+
|
| 392 |
+
elif msg_type == 'control_mode':
|
| 393 |
+
payload = data.get('data', {})
|
| 394 |
+
mode = payload.get('mode', 'ik')
|
| 395 |
+
with mujoco_lock:
|
| 396 |
+
if env is not None and current_robot == "ur5":
|
| 397 |
+
env.set_control_mode(mode)
|
| 398 |
+
|
| 399 |
+
elif msg_type == 'joint_positions':
|
| 400 |
+
payload = data.get('data', {})
|
| 401 |
+
positions = payload.get('positions', [])
|
| 402 |
+
if len(positions) == 6:
|
| 403 |
+
with mujoco_lock:
|
| 404 |
+
if env is not None and current_robot == "ur5":
|
| 405 |
+
env.set_joint_positions(positions)
|
| 406 |
+
|
| 407 |
|
| 408 |
@sock.route(f'{API_PREFIX}/ws')
|
| 409 |
def websocket_handler(ws):
|
|
|
|
| 435 |
print('WebSocket client disconnected')
|
| 436 |
|
| 437 |
|
| 438 |
+
# Serve UI at /nova-sim (no redirect)
|
| 439 |
+
@app.route('/nova-sim')
|
| 440 |
+
@app.route('/nova-sim/')
|
| 441 |
+
def nova_sim_ui():
|
| 442 |
+
return index()
|
| 443 |
+
|
| 444 |
+
|
| 445 |
+
# Redirect root to /nova-sim
|
| 446 |
@app.route('/')
|
| 447 |
def root_redirect():
|
| 448 |
return render_template_string("""
|
| 449 |
<!DOCTYPE html>
|
| 450 |
<html>
|
| 451 |
<head>
|
| 452 |
+
<meta http-equiv="refresh" content="0; url='/nova-sim'" />
|
| 453 |
</head>
|
| 454 |
<body>
|
| 455 |
+
<p>Redirecting to <a href="/nova-sim">/nova-sim</a>...</p>
|
| 456 |
</body>
|
| 457 |
</html>
|
| 458 |
""")
|
|
|
|
| 547 |
margin-top: 10px;
|
| 548 |
font-size: 0.8em;
|
| 549 |
}
|
| 550 |
+
.arm-controls { display: none; }
|
| 551 |
+
.arm-controls.active { display: block; }
|
| 552 |
+
.locomotion-controls { display: block; }
|
| 553 |
+
.locomotion-controls.hidden { display: none; }
|
| 554 |
+
.gripper-btns { display: flex; gap: 10px; margin: 10px 0; }
|
| 555 |
+
.gripper-btns button { flex: 1; }
|
| 556 |
+
.target-sliders { margin: 10px 0; }
|
| 557 |
+
.target-sliders .slider-row { margin-bottom: 8px; }
|
| 558 |
+
.target-sliders label { width: 20px; display: inline-block; }
|
| 559 |
+
.mode-toggle { display: flex; gap: 5px; margin-bottom: 15px; }
|
| 560 |
+
.mode-toggle button {
|
| 561 |
+
flex: 1; padding: 8px;
|
| 562 |
+
background: rgba(255, 255, 255, 0.1);
|
| 563 |
+
border: 1px solid rgba(255, 255, 255, 0.2);
|
| 564 |
+
}
|
| 565 |
+
.mode-toggle button.active {
|
| 566 |
+
background: rgba(52, 152, 219, 0.5);
|
| 567 |
+
border-color: rgba(52, 152, 219, 0.7);
|
| 568 |
+
}
|
| 569 |
+
.ik-controls, .joint-controls { display: none; }
|
| 570 |
+
.ik-controls.active, .joint-controls.active { display: block; }
|
| 571 |
+
.joint-sliders .slider-row { margin-bottom: 6px; }
|
| 572 |
+
.joint-sliders label { width: 40px; display: inline-block; font-size: 0.75em; }
|
| 573 |
</style>
|
| 574 |
</head>
|
| 575 |
<body>
|
|
|
|
| 587 |
<select id="robot_select" onchange="switchRobot()">
|
| 588 |
<option value="g1">Unitree G1 (Humanoid)</option>
|
| 589 |
<option value="spot">Boston Dynamics Spot (Quadruped)</option>
|
| 590 |
+
<option value="ur5">Universal Robots UR5e (Arm)</option>
|
| 591 |
</select>
|
| 592 |
<div class="robot-info" id="robot_info">
|
| 593 |
29 DOF humanoid with RL walking policy
|
| 594 |
</div>
|
| 595 |
</div>
|
| 596 |
|
| 597 |
+
<!-- Locomotion controls (G1, Spot) -->
|
| 598 |
+
<div class="locomotion-controls" id="locomotion_controls">
|
| 599 |
+
<div class="control-group">
|
| 600 |
+
<label>Walking Controls (WASD or buttons)</label>
|
| 601 |
+
<div class="rl-buttons">
|
| 602 |
+
<div class="rl-row">
|
| 603 |
+
<button class="rl-btn" onmousedown="setCmd(0.8, 0, 0)" onmouseup="setCmd(0,0,0)" ontouchstart="setCmd(0.8, 0, 0)" ontouchend="setCmd(0,0,0)">W Forward</button>
|
| 604 |
+
</div>
|
| 605 |
+
<div class="rl-row">
|
| 606 |
+
<button class="rl-btn" onmousedown="setCmd(0, 0, 1.2)" onmouseup="setCmd(0,0,0)" ontouchstart="setCmd(0, 0, 1.2)" ontouchend="setCmd(0,0,0)">A Turn L</button>
|
| 607 |
+
<button class="rl-btn" onmousedown="setCmd(-0.5, 0, 0)" onmouseup="setCmd(0,0,0)" ontouchstart="setCmd(-0.5, 0, 0)" ontouchend="setCmd(0,0,0)">S Back</button>
|
| 608 |
+
<button class="rl-btn" onmousedown="setCmd(0, 0, -1.2)" onmouseup="setCmd(0,0,0)" ontouchstart="setCmd(0, 0, -1.2)" ontouchend="setCmd(0,0,0)">D Turn R</button>
|
| 609 |
+
</div>
|
| 610 |
+
<div class="rl-row">
|
| 611 |
+
<button class="rl-btn" onmousedown="setCmd(0, 0.4, 0)" onmouseup="setCmd(0,0,0)" ontouchstart="setCmd(0, 0.4, 0)" ontouchend="setCmd(0,0,0)">Q Strafe L</button>
|
| 612 |
+
<button class="rl-btn stop" onclick="setCmd(0, 0, 0)">Stop</button>
|
| 613 |
+
<button class="rl-btn" onmousedown="setCmd(0, -0.4, 0)" onmouseup="setCmd(0,0,0)" ontouchstart="setCmd(0, -0.4, 0)" ontouchend="setCmd(0,0,0)">E Strafe R</button>
|
| 614 |
+
</div>
|
| 615 |
</div>
|
| 616 |
+
<div class="cmd-display">
|
| 617 |
+
Cmd: vx=<span id="cmd_vx">0.0</span> vy=<span id="cmd_vy">0.0</span> yaw=<span id="cmd_yaw">0.0</span>
|
|
|
|
|
|
|
| 618 |
</div>
|
| 619 |
</div>
|
| 620 |
+
|
| 621 |
+
<div class="stats" id="locomotion_stats">
|
| 622 |
+
<strong>Robot State:</strong><br>
|
| 623 |
+
Base Height: <span id="height_val">0.00</span> m<br>
|
| 624 |
+
Upright Score: <span id="upright_val">0.00</span><br>
|
| 625 |
+
Step Count: <span id="step_val">0</span>
|
| 626 |
</div>
|
| 627 |
</div>
|
| 628 |
|
| 629 |
+
<!-- Arm controls (UR5) -->
|
| 630 |
+
<div class="arm-controls" id="arm_controls">
|
| 631 |
+
<div class="control-group">
|
| 632 |
+
<label>Control Mode</label>
|
| 633 |
+
<div class="mode-toggle">
|
| 634 |
+
<button id="mode_ik" class="active" onclick="setControlMode('ik')">IK (XYZ Target)</button>
|
| 635 |
+
<button id="mode_joint" onclick="setControlMode('joint')">Direct Joints</button>
|
| 636 |
+
</div>
|
| 637 |
+
</div>
|
| 638 |
|
| 639 |
+
<!-- IK Controls -->
|
| 640 |
+
<div class="ik-controls active" id="ik_controls">
|
| 641 |
+
<div class="control-group">
|
| 642 |
+
<label>Target Position (XYZ)</label>
|
| 643 |
+
<div class="target-sliders">
|
| 644 |
+
<div class="slider-row">
|
| 645 |
+
<label>X</label>
|
| 646 |
+
<input type="range" id="target_x" min="0.1" max="0.7" step="0.01" value="0.4" oninput="updateTarget()">
|
| 647 |
+
<span class="val-display" id="target_x_val">0.40</span>
|
| 648 |
+
</div>
|
| 649 |
+
<div class="slider-row">
|
| 650 |
+
<label>Y</label>
|
| 651 |
+
<input type="range" id="target_y" min="-0.5" max="0.5" step="0.01" value="0.0" oninput="updateTarget()">
|
| 652 |
+
<span class="val-display" id="target_y_val">0.00</span>
|
| 653 |
+
</div>
|
| 654 |
+
<div class="slider-row">
|
| 655 |
+
<label>Z</label>
|
| 656 |
+
<input type="range" id="target_z" min="0.3" max="1.0" step="0.01" value="0.6" oninput="updateTarget()">
|
| 657 |
+
<span class="val-display" id="target_z_val">0.60</span>
|
| 658 |
+
</div>
|
| 659 |
+
</div>
|
| 660 |
+
</div>
|
| 661 |
+
</div>
|
| 662 |
+
|
| 663 |
+
<!-- Joint Controls -->
|
| 664 |
+
<div class="joint-controls" id="joint_controls">
|
| 665 |
+
<div class="control-group">
|
| 666 |
+
<label>Joint Positions (radians)</label>
|
| 667 |
+
<div class="joint-sliders">
|
| 668 |
+
<div class="slider-row">
|
| 669 |
+
<label>J1</label>
|
| 670 |
+
<input type="range" id="joint_0" min="-6.28" max="6.28" step="0.01" value="-1.57" oninput="updateJoints()">
|
| 671 |
+
<span class="val-display" id="joint_0_val">-1.57</span>
|
| 672 |
+
</div>
|
| 673 |
+
<div class="slider-row">
|
| 674 |
+
<label>J2</label>
|
| 675 |
+
<input type="range" id="joint_1" min="-6.28" max="6.28" step="0.01" value="-1.57" oninput="updateJoints()">
|
| 676 |
+
<span class="val-display" id="joint_1_val">-1.57</span>
|
| 677 |
+
</div>
|
| 678 |
+
<div class="slider-row">
|
| 679 |
+
<label>J3</label>
|
| 680 |
+
<input type="range" id="joint_2" min="-3.14" max="3.14" step="0.01" value="1.57" oninput="updateJoints()">
|
| 681 |
+
<span class="val-display" id="joint_2_val">1.57</span>
|
| 682 |
+
</div>
|
| 683 |
+
<div class="slider-row">
|
| 684 |
+
<label>J4</label>
|
| 685 |
+
<input type="range" id="joint_3" min="-6.28" max="6.28" step="0.01" value="-1.57" oninput="updateJoints()">
|
| 686 |
+
<span class="val-display" id="joint_3_val">-1.57</span>
|
| 687 |
+
</div>
|
| 688 |
+
<div class="slider-row">
|
| 689 |
+
<label>J5</label>
|
| 690 |
+
<input type="range" id="joint_4" min="-6.28" max="6.28" step="0.01" value="-1.57" oninput="updateJoints()">
|
| 691 |
+
<span class="val-display" id="joint_4_val">-1.57</span>
|
| 692 |
+
</div>
|
| 693 |
+
<div class="slider-row">
|
| 694 |
+
<label>J6</label>
|
| 695 |
+
<input type="range" id="joint_5" min="-6.28" max="6.28" step="0.01" value="0.0" oninput="updateJoints()">
|
| 696 |
+
<span class="val-display" id="joint_5_val">0.00</span>
|
| 697 |
+
</div>
|
| 698 |
+
</div>
|
| 699 |
+
<button style="margin-top: 8px; width: 100%;" onclick="goToHome()">Go to Home Position</button>
|
| 700 |
+
</div>
|
| 701 |
+
</div>
|
| 702 |
+
|
| 703 |
+
<div class="control-group">
|
| 704 |
+
<label>Gripper</label>
|
| 705 |
+
<div class="gripper-btns">
|
| 706 |
+
<button class="rl-btn" onclick="setGripper('open')">Open</button>
|
| 707 |
+
<button class="rl-btn" onclick="setGripper('close')">Close</button>
|
| 708 |
+
</div>
|
| 709 |
+
</div>
|
| 710 |
+
|
| 711 |
+
<div class="stats" id="arm_stats">
|
| 712 |
+
<strong>Arm State:</strong><br>
|
| 713 |
+
End Effector: <span id="ee_pos">0.00, 0.00, 0.00</span><br>
|
| 714 |
+
Joints: <span id="joint_pos_display">0.00, 0.00, 0.00, 0.00, 0.00, 0.00</span><br>
|
| 715 |
+
Mode: <span id="control_mode_display">IK</span> | Gripper: <span id="gripper_val">50%</span><br>
|
| 716 |
+
Step Count: <span id="arm_step_val">0</span>
|
| 717 |
+
</div>
|
| 718 |
</div>
|
| 719 |
|
| 720 |
+
<button class="danger" onclick="resetEnv()">Reset Environment</button>
|
| 721 |
+
|
| 722 |
<div class="camera-controls">
|
| 723 |
<div class="control-group">
|
| 724 |
<label>Camera Distance</label>
|
|
|
|
| 755 |
|
| 756 |
const robotInfoText = {
|
| 757 |
'g1': '29 DOF humanoid with RL walking policy',
|
| 758 |
+
'spot': '12 DOF quadruped with trot gait controller',
|
| 759 |
+
'ur5': '6 DOF robot arm with Robotiq gripper'
|
| 760 |
};
|
| 761 |
|
| 762 |
const robotTitles = {
|
| 763 |
'g1': 'Unitree G1 Humanoid',
|
| 764 |
+
'spot': 'Boston Dynamics Spot',
|
| 765 |
+
'ur5': 'Universal Robots UR5e'
|
| 766 |
};
|
| 767 |
|
| 768 |
+
const locomotionControls = document.getElementById('locomotion_controls');
|
| 769 |
+
const armControls = document.getElementById('arm_controls');
|
| 770 |
+
|
| 771 |
function connect() {
|
| 772 |
ws = new WebSocket(WS_URL);
|
| 773 |
|
|
|
|
| 802 |
const msg = JSON.parse(event.data);
|
| 803 |
if (msg.type === 'state') {
|
| 804 |
const data = msg.data;
|
| 805 |
+
|
| 806 |
+
if (data.robot === 'ur5') {
|
| 807 |
+
// UR5 state
|
| 808 |
+
const ee = data.end_effector;
|
| 809 |
+
document.getElementById('ee_pos').innerText =
|
| 810 |
+
ee.x.toFixed(2) + ', ' + ee.y.toFixed(2) + ', ' + ee.z.toFixed(2);
|
| 811 |
+
document.getElementById('gripper_val').innerText =
|
| 812 |
+
((255 - data.gripper) / 255 * 100).toFixed(0) + '%';
|
| 813 |
+
document.getElementById('arm_step_val').innerText = data.steps;
|
| 814 |
+
|
| 815 |
+
// Update joint position display
|
| 816 |
+
if (data.joint_positions) {
|
| 817 |
+
const jp = data.joint_positions;
|
| 818 |
+
document.getElementById('joint_pos_display').innerText =
|
| 819 |
+
jp.map(j => j.toFixed(2)).join(', ');
|
| 820 |
+
}
|
| 821 |
+
|
| 822 |
+
// Update control mode display
|
| 823 |
+
if (data.control_mode) {
|
| 824 |
+
document.getElementById('control_mode_display').innerText =
|
| 825 |
+
data.control_mode === 'ik' ? 'IK' : 'Joint';
|
| 826 |
+
// Sync UI if mode changed externally
|
| 827 |
+
if (currentControlMode !== data.control_mode) {
|
| 828 |
+
setControlMode(data.control_mode);
|
| 829 |
+
}
|
| 830 |
+
}
|
| 831 |
+
} else {
|
| 832 |
+
// Locomotion state
|
| 833 |
+
heightVal.innerText = data.base_height.toFixed(2);
|
| 834 |
+
uprightVal.innerText = data.upright.toFixed(2);
|
| 835 |
+
stepVal.innerText = data.steps;
|
| 836 |
+
cmdVx.innerText = data.vx.toFixed(1);
|
| 837 |
+
cmdVy.innerText = data.vy.toFixed(1);
|
| 838 |
+
cmdYaw.innerText = data.vyaw.toFixed(1);
|
| 839 |
+
}
|
| 840 |
|
| 841 |
if (data.robot && robotSelect.value !== data.robot) {
|
| 842 |
robotSelect.value = data.robot;
|
|
|
|
| 858 |
function updateRobotUI(robot) {
|
| 859 |
robotTitle.innerText = robotTitles[robot] || robot;
|
| 860 |
robotInfo.innerText = robotInfoText[robot] || '';
|
| 861 |
+
|
| 862 |
+
// Toggle controls based on robot type
|
| 863 |
+
if (robot === 'ur5') {
|
| 864 |
+
locomotionControls.classList.add('hidden');
|
| 865 |
+
armControls.classList.add('active');
|
| 866 |
+
} else {
|
| 867 |
+
locomotionControls.classList.remove('hidden');
|
| 868 |
+
armControls.classList.remove('active');
|
| 869 |
+
}
|
| 870 |
}
|
| 871 |
|
| 872 |
function switchRobot() {
|
|
|
|
| 900 |
send('camera_follow', {follow});
|
| 901 |
}
|
| 902 |
|
| 903 |
+
// UR5 controls
|
| 904 |
+
let currentControlMode = 'ik';
|
| 905 |
+
|
| 906 |
+
function setControlMode(mode) {
|
| 907 |
+
currentControlMode = mode;
|
| 908 |
+
send('control_mode', {mode});
|
| 909 |
+
|
| 910 |
+
// Update UI
|
| 911 |
+
document.getElementById('mode_ik').classList.toggle('active', mode === 'ik');
|
| 912 |
+
document.getElementById('mode_joint').classList.toggle('active', mode === 'joint');
|
| 913 |
+
document.getElementById('ik_controls').classList.toggle('active', mode === 'ik');
|
| 914 |
+
document.getElementById('joint_controls').classList.toggle('active', mode === 'joint');
|
| 915 |
+
}
|
| 916 |
+
|
| 917 |
+
function updateTarget() {
|
| 918 |
+
const x = parseFloat(document.getElementById('target_x').value);
|
| 919 |
+
const y = parseFloat(document.getElementById('target_y').value);
|
| 920 |
+
const z = parseFloat(document.getElementById('target_z').value);
|
| 921 |
+
document.getElementById('target_x_val').innerText = x.toFixed(2);
|
| 922 |
+
document.getElementById('target_y_val').innerText = y.toFixed(2);
|
| 923 |
+
document.getElementById('target_z_val').innerText = z.toFixed(2);
|
| 924 |
+
send('arm_target', {x, y, z});
|
| 925 |
+
}
|
| 926 |
+
|
| 927 |
+
function updateJoints() {
|
| 928 |
+
const positions = [];
|
| 929 |
+
for (let i = 0; i < 6; i++) {
|
| 930 |
+
const val = parseFloat(document.getElementById('joint_' + i).value);
|
| 931 |
+
positions.push(val);
|
| 932 |
+
document.getElementById('joint_' + i + '_val').innerText = val.toFixed(2);
|
| 933 |
+
}
|
| 934 |
+
send('joint_positions', {positions});
|
| 935 |
+
}
|
| 936 |
+
|
| 937 |
+
function goToHome() {
|
| 938 |
+
// UR5 home position
|
| 939 |
+
const home = [-1.57, -1.57, 1.57, -1.57, -1.57, 0.0];
|
| 940 |
+
for (let i = 0; i < 6; i++) {
|
| 941 |
+
document.getElementById('joint_' + i).value = home[i];
|
| 942 |
+
document.getElementById('joint_' + i + '_val').innerText = home[i].toFixed(2);
|
| 943 |
+
}
|
| 944 |
+
send('joint_positions', {positions: home});
|
| 945 |
+
}
|
| 946 |
+
|
| 947 |
+
function setGripper(action) {
|
| 948 |
+
send('gripper', {action});
|
| 949 |
+
}
|
| 950 |
+
|
| 951 |
function updateCmdFromKeys() {
|
| 952 |
let vx = 0, vy = 0, vyaw = 0;
|
| 953 |
if (keysPressed.has('KeyW') || keysPressed.has('ArrowUp')) vx = 0.8;
|
robots/ur5/controllers/ik_controller.py
ADDED
|
@@ -0,0 +1,161 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
"""Inverse Kinematics controller for UR5e using damped least squares."""
|
| 2 |
+
import numpy as np
|
| 3 |
+
import mujoco
|
| 4 |
+
|
| 5 |
+
|
| 6 |
+
class IKController:
|
| 7 |
+
"""
|
| 8 |
+
IK controller using MuJoCo's built-in Jacobian computation
|
| 9 |
+
and damped least squares for stable inverse kinematics.
|
| 10 |
+
"""
|
| 11 |
+
|
| 12 |
+
def __init__(self, model, data, ee_site_name="ee_site", arm_joint_names=None):
|
| 13 |
+
"""
|
| 14 |
+
Initialize IK controller.
|
| 15 |
+
|
| 16 |
+
Args:
|
| 17 |
+
model: MuJoCo model
|
| 18 |
+
data: MuJoCo data
|
| 19 |
+
ee_site_name: Name of the end-effector site
|
| 20 |
+
arm_joint_names: List of joint names to control
|
| 21 |
+
"""
|
| 22 |
+
self.model = model
|
| 23 |
+
self.data = data
|
| 24 |
+
|
| 25 |
+
# Get site ID
|
| 26 |
+
self.ee_site_id = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_SITE, ee_site_name)
|
| 27 |
+
if self.ee_site_id < 0:
|
| 28 |
+
raise ValueError(f"Site '{ee_site_name}' not found in model")
|
| 29 |
+
|
| 30 |
+
# Get joint IDs
|
| 31 |
+
self.joint_ids = []
|
| 32 |
+
self.dof_ids = []
|
| 33 |
+
|
| 34 |
+
if arm_joint_names is None:
|
| 35 |
+
arm_joint_names = [
|
| 36 |
+
"shoulder_pan_joint",
|
| 37 |
+
"shoulder_lift_joint",
|
| 38 |
+
"elbow_joint",
|
| 39 |
+
"wrist_1_joint",
|
| 40 |
+
"wrist_2_joint",
|
| 41 |
+
"wrist_3_joint",
|
| 42 |
+
]
|
| 43 |
+
|
| 44 |
+
for name in arm_joint_names:
|
| 45 |
+
jnt_id = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_JOINT, name)
|
| 46 |
+
if jnt_id < 0:
|
| 47 |
+
raise ValueError(f"Joint '{name}' not found in model")
|
| 48 |
+
self.joint_ids.append(jnt_id)
|
| 49 |
+
# Get the DOF address for this joint
|
| 50 |
+
self.dof_ids.append(model.jnt_dofadr[jnt_id])
|
| 51 |
+
|
| 52 |
+
self.num_joints = len(self.joint_ids)
|
| 53 |
+
|
| 54 |
+
# IK parameters
|
| 55 |
+
self.damping = 0.01 # Damping factor for stability
|
| 56 |
+
self.max_iterations = 50
|
| 57 |
+
self.tolerance = 0.001 # Position tolerance in meters
|
| 58 |
+
self.step_size = 0.5 # Step size for gradient descent
|
| 59 |
+
|
| 60 |
+
# Joint limits (from model)
|
| 61 |
+
self.joint_limits_low = np.array([model.jnt_range[jid, 0] for jid in self.joint_ids])
|
| 62 |
+
self.joint_limits_high = np.array([model.jnt_range[jid, 1] for jid in self.joint_ids])
|
| 63 |
+
|
| 64 |
+
# Preallocate Jacobian arrays
|
| 65 |
+
self.jacp = np.zeros((3, model.nv))
|
| 66 |
+
self.jacr = np.zeros((3, model.nv))
|
| 67 |
+
|
| 68 |
+
def get_current_joint_positions(self):
|
| 69 |
+
"""Get current positions of controlled joints."""
|
| 70 |
+
return np.array([self.data.qpos[self.model.jnt_qposadr[jid]] for jid in self.joint_ids])
|
| 71 |
+
|
| 72 |
+
def get_ee_position(self):
|
| 73 |
+
"""Get current end-effector position."""
|
| 74 |
+
return self.data.site_xpos[self.ee_site_id].copy()
|
| 75 |
+
|
| 76 |
+
def compute_jacobian(self):
|
| 77 |
+
"""Compute the Jacobian for the end-effector site."""
|
| 78 |
+
# Zero out arrays
|
| 79 |
+
self.jacp.fill(0)
|
| 80 |
+
self.jacr.fill(0)
|
| 81 |
+
|
| 82 |
+
# Compute Jacobian using MuJoCo
|
| 83 |
+
mujoco.mj_jacSite(self.model, self.data, self.jacp, self.jacr, self.ee_site_id)
|
| 84 |
+
|
| 85 |
+
# Extract columns corresponding to controlled joints
|
| 86 |
+
jac = np.zeros((3, self.num_joints))
|
| 87 |
+
for i, dof_id in enumerate(self.dof_ids):
|
| 88 |
+
jac[:, i] = self.jacp[:, dof_id]
|
| 89 |
+
|
| 90 |
+
return jac
|
| 91 |
+
|
| 92 |
+
def compute_ik(self, target_pos, current_qpos=None):
|
| 93 |
+
"""
|
| 94 |
+
Compute joint positions to reach target position using damped least squares.
|
| 95 |
+
|
| 96 |
+
Args:
|
| 97 |
+
target_pos: Target position [x, y, z]
|
| 98 |
+
current_qpos: Starting joint positions (uses current if None)
|
| 99 |
+
|
| 100 |
+
Returns:
|
| 101 |
+
Joint positions to reach target
|
| 102 |
+
"""
|
| 103 |
+
if current_qpos is None:
|
| 104 |
+
qpos = self.get_current_joint_positions()
|
| 105 |
+
else:
|
| 106 |
+
qpos = current_qpos.copy()
|
| 107 |
+
|
| 108 |
+
target = np.array(target_pos)
|
| 109 |
+
|
| 110 |
+
for _ in range(self.max_iterations):
|
| 111 |
+
# Update forward kinematics
|
| 112 |
+
for i, jid in enumerate(self.joint_ids):
|
| 113 |
+
self.data.qpos[self.model.jnt_qposadr[jid]] = qpos[i]
|
| 114 |
+
mujoco.mj_forward(self.model, self.data)
|
| 115 |
+
|
| 116 |
+
# Get current end-effector position
|
| 117 |
+
ee_pos = self.get_ee_position()
|
| 118 |
+
|
| 119 |
+
# Compute error
|
| 120 |
+
error = target - ee_pos
|
| 121 |
+
error_norm = np.linalg.norm(error)
|
| 122 |
+
|
| 123 |
+
# Check convergence
|
| 124 |
+
if error_norm < self.tolerance:
|
| 125 |
+
break
|
| 126 |
+
|
| 127 |
+
# Compute Jacobian
|
| 128 |
+
jac = self.compute_jacobian()
|
| 129 |
+
|
| 130 |
+
# Damped least squares: dq = J^T * (J * J^T + lambda^2 * I)^-1 * error
|
| 131 |
+
jjt = jac @ jac.T
|
| 132 |
+
damped = jjt + self.damping**2 * np.eye(3)
|
| 133 |
+
dq = jac.T @ np.linalg.solve(damped, error)
|
| 134 |
+
|
| 135 |
+
# Apply step
|
| 136 |
+
qpos = qpos + self.step_size * dq
|
| 137 |
+
|
| 138 |
+
# Clamp to joint limits
|
| 139 |
+
qpos = np.clip(qpos, self.joint_limits_low, self.joint_limits_high)
|
| 140 |
+
|
| 141 |
+
return qpos
|
| 142 |
+
|
| 143 |
+
def compute_ik_with_orientation(self, target_pos, target_quat=None, current_qpos=None):
|
| 144 |
+
"""
|
| 145 |
+
Compute joint positions to reach target pose (position + orientation).
|
| 146 |
+
|
| 147 |
+
Args:
|
| 148 |
+
target_pos: Target position [x, y, z]
|
| 149 |
+
target_quat: Target orientation quaternion [w, x, y, z] (optional)
|
| 150 |
+
current_qpos: Starting joint positions (uses current if None)
|
| 151 |
+
|
| 152 |
+
Returns:
|
| 153 |
+
Joint positions to reach target
|
| 154 |
+
"""
|
| 155 |
+
# For now, just use position-only IK
|
| 156 |
+
# Full 6-DOF IK would need to include orientation in the error
|
| 157 |
+
return self.compute_ik(target_pos, current_qpos)
|
| 158 |
+
|
| 159 |
+
def reset(self):
|
| 160 |
+
"""Reset controller state."""
|
| 161 |
+
pass
|
robots/ur5/model/assets/base.stl
ADDED
|
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
version https://git-lfs.github.com/spec/v1
|
| 2 |
+
oid sha256:1c7b9f2bd92d705fc4e897c94e905973a3c05f406845e942229433deb7041453
|
| 3 |
+
size 1712484
|
robots/ur5/model/assets/base_0.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/base_1.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/base_mount.stl
ADDED
|
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
version https://git-lfs.github.com/spec/v1
|
| 2 |
+
oid sha256:87971dfdd6e5311b5a723e7b73c4701ebf5c2364df671500f30dfc1c53c8e61a
|
| 3 |
+
size 1091784
|
robots/ur5/model/assets/coupler.stl
ADDED
|
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
version https://git-lfs.github.com/spec/v1
|
| 2 |
+
oid sha256:d5ee95e62f8415bf5b6e503c831a958f5fc1990bf9b2865329ec38a28932727c
|
| 3 |
+
size 89084
|
robots/ur5/model/assets/driver.stl
ADDED
|
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
version https://git-lfs.github.com/spec/v1
|
| 2 |
+
oid sha256:bbd6e868b1778bead60d2516c7ede581d7ad4e431744b1828757d6ea5129c112
|
| 3 |
+
size 67084
|
robots/ur5/model/assets/follower.stl
ADDED
|
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
version https://git-lfs.github.com/spec/v1
|
| 2 |
+
oid sha256:633793332c081641ce200df27a40643cc293b29956e3cb5cb29cb811c33ef1c7
|
| 3 |
+
size 110484
|
robots/ur5/model/assets/forearm_0.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/forearm_1.obj
ADDED
|
@@ -0,0 +1,2159 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
mtllib JointGrey.001.mtl
|
| 2 |
+
usemtl JointGrey.001
|
| 3 |
+
v 0.00119500 0.04752100 0.07649100
|
| 4 |
+
v 0.00119500 0.04752100 0.07649100
|
| 5 |
+
v 0.00119500 0.04752100 0.07649100
|
| 6 |
+
v 0.00832200 0.04679500 0.07649300
|
| 7 |
+
v 0.00832200 0.04679500 0.07649300
|
| 8 |
+
v 0.01475300 0.04519700 0.07649200
|
| 9 |
+
v 0.01475300 0.04519700 0.07649200
|
| 10 |
+
v 0.01475300 0.04519700 0.07649200
|
| 11 |
+
v 0.01475300 0.04519700 0.07649200
|
| 12 |
+
v 0.02103800 0.04265800 0.07649200
|
| 13 |
+
v 0.02103800 0.04265800 0.07649200
|
| 14 |
+
v 0.02103800 0.04265800 0.07649200
|
| 15 |
+
v 0.02541600 0.04019400 0.07649200
|
| 16 |
+
v 0.02541600 0.04019400 0.07649200
|
| 17 |
+
v 0.02541600 0.04019400 0.07649200
|
| 18 |
+
v 0.03171900 0.03554200 0.07649100
|
| 19 |
+
v 0.03171900 0.03554200 0.07649100
|
| 20 |
+
v 0.03171900 0.03554200 0.07649100
|
| 21 |
+
v 0.03671100 0.03040400 0.07649300
|
| 22 |
+
v 0.03671100 0.03040400 0.07649300
|
| 23 |
+
v 0.04061100 0.02504600 0.07649200
|
| 24 |
+
v 0.04061100 0.02504600 0.07649200
|
| 25 |
+
v 0.04061100 0.02504600 0.07649200
|
| 26 |
+
v 0.04061100 0.02504600 0.07649200
|
| 27 |
+
v 0.04379400 0.01906100 0.07649200
|
| 28 |
+
v 0.04379400 0.01906100 0.07649200
|
| 29 |
+
v 0.04379400 0.01906100 0.07649200
|
| 30 |
+
v 0.04556400 0.01436000 0.07649200
|
| 31 |
+
v 0.04556400 0.01436000 0.07649200
|
| 32 |
+
v 0.04556400 0.01436000 0.07649200
|
| 33 |
+
v 0.04740100 0.00674400 0.07649100
|
| 34 |
+
v 0.04740100 0.00674400 0.07649100
|
| 35 |
+
v 0.04740100 0.00674400 0.07649100
|
| 36 |
+
v 0.04792300 -0.00040000 0.07649300
|
| 37 |
+
v 0.04792300 -0.00040000 0.07649300
|
| 38 |
+
v 0.04746600 -0.00701100 0.07649200
|
| 39 |
+
v 0.04746600 -0.00701100 0.07649200
|
| 40 |
+
v 0.04746600 -0.00701100 0.07649200
|
| 41 |
+
v 0.04746600 -0.00701100 0.07649200
|
| 42 |
+
v 0.04605800 -0.01364200 0.07649200
|
| 43 |
+
v 0.04605800 -0.01364200 0.07649200
|
| 44 |
+
v 0.04605800 -0.01364200 0.07649200
|
| 45 |
+
v 0.04439100 -0.01838100 0.07649200
|
| 46 |
+
v 0.04439100 -0.01838100 0.07649200
|
| 47 |
+
v 0.04439100 -0.01838100 0.07649200
|
| 48 |
+
v 0.04090300 -0.02539600 0.07649100
|
| 49 |
+
v 0.04090300 -0.02539600 0.07649100
|
| 50 |
+
v 0.04090300 -0.02539600 0.07649100
|
| 51 |
+
v 0.03671100 -0.03120400 0.07649300
|
| 52 |
+
v 0.03671100 -0.03120400 0.07649300
|
| 53 |
+
v 0.03211200 -0.03597500 0.07649200
|
| 54 |
+
v 0.03211200 -0.03597500 0.07649200
|
| 55 |
+
v 0.03211200 -0.03597500 0.07649200
|
| 56 |
+
v 0.03211200 -0.03597500 0.07649200
|
| 57 |
+
v 0.02677100 -0.04014900 0.07649200
|
| 58 |
+
v 0.02677100 -0.04014900 0.07649200
|
| 59 |
+
v 0.02677100 -0.04014900 0.07649200
|
| 60 |
+
v 0.02244800 -0.04270800 0.07649200
|
| 61 |
+
v 0.02244800 -0.04270800 0.07649200
|
| 62 |
+
v 0.02244800 -0.04270800 0.07649200
|
| 63 |
+
v 0.01526700 -0.04584000 0.07649100
|
| 64 |
+
v 0.01526700 -0.04584000 0.07649100
|
| 65 |
+
v 0.01526700 -0.04584000 0.07649100
|
| 66 |
+
v 0.00832200 -0.04759500 0.07649300
|
| 67 |
+
v 0.00832200 -0.04759500 0.07649300
|
| 68 |
+
v 0.00116900 -0.04832600 0.07649200
|
| 69 |
+
v 0.00116900 -0.04832600 0.07649200
|
| 70 |
+
v 0.00116900 -0.04832600 0.07649200
|
| 71 |
+
v 0.00116900 -0.04832600 0.07649200
|
| 72 |
+
v -0.00539400 -0.04801100 0.07649200
|
| 73 |
+
v -0.00539400 -0.04801100 0.07649200
|
| 74 |
+
v -0.00539400 -0.04801100 0.07649200
|
| 75 |
+
v -0.00999900 -0.04723900 0.07649200
|
| 76 |
+
v -0.00999900 -0.04723900 0.07649200
|
| 77 |
+
v -0.00999900 -0.04723900 0.07649200
|
| 78 |
+
v -0.01751300 -0.04502300 0.07649100
|
| 79 |
+
v -0.01751300 -0.04502300 0.07649100
|
| 80 |
+
v -0.01751300 -0.04502300 0.07649100
|
| 81 |
+
v -0.02396100 -0.04190200 0.07649300
|
| 82 |
+
v -0.02396100 -0.04190200 0.07649300
|
| 83 |
+
v -0.02945800 -0.03820200 0.07649200
|
| 84 |
+
v -0.02945800 -0.03820200 0.07649200
|
| 85 |
+
v -0.02945800 -0.03820200 0.07649200
|
| 86 |
+
v -0.02945800 -0.03820200 0.07649200
|
| 87 |
+
v -0.03449700 -0.03366600 0.07649200
|
| 88 |
+
v -0.03449700 -0.03366600 0.07649200
|
| 89 |
+
v -0.03449700 -0.03366600 0.07649200
|
| 90 |
+
v -0.03776800 -0.02985400 0.07649200
|
| 91 |
+
v -0.03776800 -0.02985400 0.07649200
|
| 92 |
+
v -0.03776800 -0.02985400 0.07649200
|
| 93 |
+
v -0.04209900 -0.02332600 0.07649100
|
| 94 |
+
v -0.04209900 -0.02332600 0.07649100
|
| 95 |
+
v -0.04209900 -0.02332600 0.07649100
|
| 96 |
+
v -0.04503300 -0.01679100 0.07649300
|
| 97 |
+
v -0.04503300 -0.01679100 0.07649300
|
| 98 |
+
v -0.04686500 -0.01042200 0.07649200
|
| 99 |
+
v -0.04686500 -0.01042200 0.07649200
|
| 100 |
+
v -0.04686500 -0.01042200 0.07649200
|
| 101 |
+
v -0.04686500 -0.01042200 0.07649200
|
| 102 |
+
v -0.04780900 -0.00370900 0.07649200
|
| 103 |
+
v -0.04780900 -0.00370900 0.07649200
|
| 104 |
+
v -0.04780900 -0.00370900 0.07649200
|
| 105 |
+
v -0.04786400 0.00131400 0.07649200
|
| 106 |
+
v -0.04786400 0.00131400 0.07649200
|
| 107 |
+
v -0.04786400 0.00131400 0.07649200
|
| 108 |
+
v -0.04698600 0.00909800 0.07649100
|
| 109 |
+
v -0.04698600 0.00909800 0.07649100
|
| 110 |
+
v -0.04698600 0.00909800 0.07649100
|
| 111 |
+
v -0.04503300 0.01599000 0.07649300
|
| 112 |
+
v -0.04503300 0.01599000 0.07649300
|
| 113 |
+
v -0.04234300 0.02204700 0.07649200
|
| 114 |
+
v -0.04234300 0.02204700 0.07649200
|
| 115 |
+
v -0.04234300 0.02204700 0.07649200
|
| 116 |
+
v -0.04234300 0.02204700 0.07649200
|
| 117 |
+
v -0.03875100 0.02779600 0.07649200
|
| 118 |
+
v -0.03875100 0.02779600 0.07649200
|
| 119 |
+
v -0.03875100 0.02779600 0.07649200
|
| 120 |
+
v -0.03556400 0.03167900 0.07649200
|
| 121 |
+
v -0.03556400 0.03167900 0.07649200
|
| 122 |
+
v -0.03556400 0.03167900 0.07649200
|
| 123 |
+
v -0.02988800 0.03707800 0.07649100
|
| 124 |
+
v -0.02988800 0.03707800 0.07649100
|
| 125 |
+
v -0.02988800 0.03707800 0.07649100
|
| 126 |
+
v -0.02396100 0.04110200 0.07649300
|
| 127 |
+
v -0.02396100 0.04110200 0.07649300
|
| 128 |
+
v -0.01800800 0.04401200 0.07649200
|
| 129 |
+
v -0.01800800 0.04401200 0.07649200
|
| 130 |
+
v -0.01800800 0.04401200 0.07649200
|
| 131 |
+
v -0.01800800 0.04401200 0.07649200
|
| 132 |
+
v -0.01156100 0.04610800 0.07649200
|
| 133 |
+
v -0.01156100 0.04610800 0.07649200
|
| 134 |
+
v -0.01156100 0.04610800 0.07649200
|
| 135 |
+
v -0.00662400 0.04703400 0.07649200
|
| 136 |
+
v -0.00662400 0.04703400 0.07649200
|
| 137 |
+
v -0.00662400 0.04703400 0.07649200
|
| 138 |
+
v -0.04773800 -0.00042700 0.07943200
|
| 139 |
+
v -0.04773800 -0.00042700 0.07943200
|
| 140 |
+
v -0.04773800 -0.00042700 0.07943200
|
| 141 |
+
v -0.04773800 -0.00042700 0.07943200
|
| 142 |
+
v -0.04773800 -0.00042700 0.07943200
|
| 143 |
+
v -0.04581100 0.01311200 0.07945600
|
| 144 |
+
v -0.04581100 0.01311200 0.07945600
|
| 145 |
+
v -0.04581100 0.01311200 0.07945600
|
| 146 |
+
v -0.04581100 0.01311200 0.07945600
|
| 147 |
+
v -0.04581100 0.01311200 0.07945600
|
| 148 |
+
v -0.04581100 0.01311200 0.07945600
|
| 149 |
+
v -0.04364000 0.01898300 0.07940700
|
| 150 |
+
v -0.04364000 0.01898300 0.07940700
|
| 151 |
+
v -0.04364000 0.01898300 0.07940700
|
| 152 |
+
v -0.04364000 0.01898300 0.07940700
|
| 153 |
+
v -0.04364000 0.01898300 0.07940700
|
| 154 |
+
v -0.04064700 0.02465500 0.07947500
|
| 155 |
+
v -0.04064700 0.02465500 0.07947500
|
| 156 |
+
v -0.04064700 0.02465500 0.07947500
|
| 157 |
+
v -0.04064700 0.02465500 0.07947500
|
| 158 |
+
v -0.04064700 0.02465500 0.07947500
|
| 159 |
+
v -0.02632100 0.03945300 0.07945900
|
| 160 |
+
v -0.02632100 0.03945300 0.07945900
|
| 161 |
+
v -0.02632100 0.03945300 0.07945900
|
| 162 |
+
v -0.02632100 0.03945300 0.07945900
|
| 163 |
+
v -0.02632100 0.03945300 0.07945900
|
| 164 |
+
v -0.02632100 0.03945300 0.07945900
|
| 165 |
+
v -0.02632100 0.03945300 0.07945900
|
| 166 |
+
v -0.02107200 0.04245000 0.07940700
|
| 167 |
+
v -0.02107200 0.04245000 0.07940700
|
| 168 |
+
v -0.02107200 0.04245000 0.07940700
|
| 169 |
+
v -0.02107200 0.04245000 0.07940700
|
| 170 |
+
v -0.01505300 0.04491400 0.07947100
|
| 171 |
+
v -0.01505300 0.04491400 0.07947100
|
| 172 |
+
v -0.01505300 0.04491400 0.07947100
|
| 173 |
+
v -0.01505300 0.04491400 0.07947100
|
| 174 |
+
v -0.01505300 0.04491400 0.07947100
|
| 175 |
+
v -0.01505300 0.04491400 0.07947100
|
| 176 |
+
v 0.00544000 0.04705500 0.07943400
|
| 177 |
+
v 0.00544000 0.04705500 0.07943400
|
| 178 |
+
v 0.00544000 0.04705500 0.07943400
|
| 179 |
+
v 0.00544000 0.04705500 0.07943400
|
| 180 |
+
v 0.00544000 0.04705500 0.07943400
|
| 181 |
+
v 0.00544000 0.04705500 0.07943400
|
| 182 |
+
v 0.00544000 0.04705500 0.07943400
|
| 183 |
+
v 0.01148900 0.04594800 0.07940600
|
| 184 |
+
v 0.01148900 0.04594800 0.07940600
|
| 185 |
+
v 0.01148900 0.04594800 0.07940600
|
| 186 |
+
v 0.01148900 0.04594800 0.07940600
|
| 187 |
+
v 0.01768000 0.04395800 0.07945900
|
| 188 |
+
v 0.01768000 0.04395800 0.07945900
|
| 189 |
+
v 0.01768000 0.04395800 0.07945900
|
| 190 |
+
v 0.01768000 0.04395800 0.07945900
|
| 191 |
+
v 0.01768000 0.04395800 0.07945900
|
| 192 |
+
v 0.01768000 0.04395800 0.07945900
|
| 193 |
+
v 0.03465300 0.03246800 0.07945700
|
| 194 |
+
v 0.03465300 0.03246800 0.07945700
|
| 195 |
+
v 0.03465300 0.03246800 0.07945700
|
| 196 |
+
v 0.03465300 0.03246800 0.07945700
|
| 197 |
+
v 0.03465300 0.03246800 0.07945700
|
| 198 |
+
v 0.03465300 0.03246800 0.07945700
|
| 199 |
+
v 0.03863200 0.02770500 0.07937400
|
| 200 |
+
v 0.03863200 0.02770500 0.07937400
|
| 201 |
+
v 0.03863200 0.02770500 0.07937400
|
| 202 |
+
v 0.03863200 0.02770500 0.07937400
|
| 203 |
+
v 0.03863200 0.02770500 0.07937400
|
| 204 |
+
v 0.04204800 0.02217900 0.07950400
|
| 205 |
+
v 0.04204800 0.02217900 0.07950400
|
| 206 |
+
v 0.04204800 0.02217900 0.07950400
|
| 207 |
+
v 0.04204800 0.02217900 0.07950400
|
| 208 |
+
v 0.04204800 0.02217900 0.07950400
|
| 209 |
+
v 0.04763700 -0.00347800 0.07947500
|
| 210 |
+
v 0.04763700 -0.00347800 0.07947500
|
| 211 |
+
v 0.04763700 -0.00347800 0.07947500
|
| 212 |
+
v 0.04763700 -0.00347800 0.07947500
|
| 213 |
+
v 0.04675800 -0.01009000 0.07946300
|
| 214 |
+
v 0.04675800 -0.01009000 0.07946300
|
| 215 |
+
v 0.04675800 -0.01009000 0.07946300
|
| 216 |
+
v 0.04675800 -0.01009000 0.07946300
|
| 217 |
+
v 0.04675800 -0.01009000 0.07946300
|
| 218 |
+
v 0.04675800 -0.01009000 0.07946300
|
| 219 |
+
v 0.03840500 -0.02879500 0.07945500
|
| 220 |
+
v 0.03840500 -0.02879500 0.07945500
|
| 221 |
+
v 0.03840500 -0.02879500 0.07945500
|
| 222 |
+
v 0.03840500 -0.02879500 0.07945500
|
| 223 |
+
v 0.03840500 -0.02879500 0.07945500
|
| 224 |
+
v 0.03840500 -0.02879500 0.07945500
|
| 225 |
+
v 0.03840500 -0.02879500 0.07945500
|
| 226 |
+
v 0.03840500 -0.02879500 0.07945500
|
| 227 |
+
v 0.03448000 -0.03343600 0.07940600
|
| 228 |
+
v 0.03448000 -0.03343600 0.07940600
|
| 229 |
+
v 0.03448000 -0.03343600 0.07940600
|
| 230 |
+
v 0.03448000 -0.03343600 0.07940600
|
| 231 |
+
v 0.02968000 -0.03780300 0.07947300
|
| 232 |
+
v 0.02968000 -0.03780300 0.07947300
|
| 233 |
+
v 0.02968000 -0.03780300 0.07947300
|
| 234 |
+
v 0.02968000 -0.03780300 0.07947300
|
| 235 |
+
v 0.02968000 -0.03780300 0.07947300
|
| 236 |
+
v 0.00526000 -0.04784500 0.07948100
|
| 237 |
+
v 0.00526000 -0.04784500 0.07948100
|
| 238 |
+
v 0.00526000 -0.04784500 0.07948100
|
| 239 |
+
v 0.00526000 -0.04784500 0.07948100
|
| 240 |
+
v 0.00526000 -0.04784500 0.07948100
|
| 241 |
+
v -0.00140100 -0.04813000 0.07946600
|
| 242 |
+
v -0.00140100 -0.04813000 0.07946600
|
| 243 |
+
v -0.00140100 -0.04813000 0.07946600
|
| 244 |
+
v -0.00140100 -0.04813000 0.07946600
|
| 245 |
+
v -0.00140100 -0.04813000 0.07946600
|
| 246 |
+
v -0.02634800 -0.04020000 0.07950200
|
| 247 |
+
v -0.02634800 -0.04020000 0.07950200
|
| 248 |
+
v -0.02634800 -0.04020000 0.07950200
|
| 249 |
+
v -0.02634800 -0.04020000 0.07950200
|
| 250 |
+
v -0.03166500 -0.03613800 0.07947300
|
| 251 |
+
v -0.03166500 -0.03613800 0.07947300
|
| 252 |
+
v -0.03166500 -0.03613800 0.07947300
|
| 253 |
+
v -0.03166500 -0.03613800 0.07947300
|
| 254 |
+
v -0.03166500 -0.03613800 0.07947300
|
| 255 |
+
v -0.03166500 -0.03613800 0.07947300
|
| 256 |
+
v -0.04580300 -0.01384000 0.07948700
|
| 257 |
+
v -0.04580300 -0.01384000 0.07948700
|
| 258 |
+
v -0.04580300 -0.01384000 0.07948700
|
| 259 |
+
v -0.04580300 -0.01384000 0.07948700
|
| 260 |
+
v -0.04724400 -0.00733200 0.07946900
|
| 261 |
+
v -0.04724400 -0.00733200 0.07946900
|
| 262 |
+
v -0.04724400 -0.00733200 0.07946900
|
| 263 |
+
v -0.04724400 -0.00733200 0.07946900
|
| 264 |
+
v -0.04724400 -0.00733200 0.07946900
|
| 265 |
+
v -0.04724400 -0.00733200 0.07946900
|
| 266 |
+
v -0.04069300 -0.02537200 0.07948400
|
| 267 |
+
v -0.04069300 -0.02537200 0.07948400
|
| 268 |
+
v -0.04069300 -0.02537200 0.07948400
|
| 269 |
+
v -0.04069300 -0.02537200 0.07948400
|
| 270 |
+
v -0.04069300 -0.02537200 0.07948400
|
| 271 |
+
v -0.04069300 -0.02537200 0.07948400
|
| 272 |
+
v -0.04374400 -0.01963000 0.07935500
|
| 273 |
+
v -0.04374400 -0.01963000 0.07935500
|
| 274 |
+
v -0.04374400 -0.01963000 0.07935500
|
| 275 |
+
v -0.04374400 -0.01963000 0.07935500
|
| 276 |
+
v -0.04374400 -0.01963000 0.07935500
|
| 277 |
+
v -0.04374400 -0.01963000 0.07935500
|
| 278 |
+
v -0.04374400 -0.01963000 0.07935500
|
| 279 |
+
v -0.03644600 -0.03122300 0.07946100
|
| 280 |
+
v -0.03644600 -0.03122300 0.07946100
|
| 281 |
+
v -0.03644600 -0.03122300 0.07946100
|
| 282 |
+
v -0.03644600 -0.03122300 0.07946100
|
| 283 |
+
v -0.03644600 -0.03122300 0.07946100
|
| 284 |
+
v -0.01503400 -0.04571500 0.07948800
|
| 285 |
+
v -0.01503400 -0.04571500 0.07948800
|
| 286 |
+
v -0.01503400 -0.04571500 0.07948800
|
| 287 |
+
v -0.01503400 -0.04571500 0.07948800
|
| 288 |
+
v -0.01503400 -0.04571500 0.07948800
|
| 289 |
+
v -0.01503400 -0.04571500 0.07948800
|
| 290 |
+
v -0.01503400 -0.04571500 0.07948800
|
| 291 |
+
v -0.02109300 -0.04327700 0.07935500
|
| 292 |
+
v -0.02109300 -0.04327700 0.07935500
|
| 293 |
+
v -0.02109300 -0.04327700 0.07935500
|
| 294 |
+
v -0.02109300 -0.04327700 0.07935500
|
| 295 |
+
v -0.02109300 -0.04327700 0.07935500
|
| 296 |
+
v -0.02109300 -0.04327700 0.07935500
|
| 297 |
+
v -0.00828400 -0.04741400 0.07943200
|
| 298 |
+
v -0.00828400 -0.04741400 0.07943200
|
| 299 |
+
v -0.00828400 -0.04741400 0.07943200
|
| 300 |
+
v -0.00828400 -0.04741400 0.07943200
|
| 301 |
+
v -0.00828400 -0.04741400 0.07943200
|
| 302 |
+
v 0.01759200 -0.04478900 0.07946800
|
| 303 |
+
v 0.01759200 -0.04478900 0.07946800
|
| 304 |
+
v 0.01759200 -0.04478900 0.07946800
|
| 305 |
+
v 0.01759200 -0.04478900 0.07946800
|
| 306 |
+
v 0.01759200 -0.04478900 0.07946800
|
| 307 |
+
v 0.01132200 -0.04682300 0.07935500
|
| 308 |
+
v 0.01132200 -0.04682300 0.07935500
|
| 309 |
+
v 0.01132200 -0.04682300 0.07935500
|
| 310 |
+
v 0.01132200 -0.04682300 0.07935500
|
| 311 |
+
v 0.01132200 -0.04682300 0.07935500
|
| 312 |
+
v 0.01132200 -0.04682300 0.07935500
|
| 313 |
+
v 0.01132200 -0.04682300 0.07935500
|
| 314 |
+
v 0.02399800 -0.04166000 0.07946200
|
| 315 |
+
v 0.02399800 -0.04166000 0.07946200
|
| 316 |
+
v 0.02399800 -0.04166000 0.07946200
|
| 317 |
+
v 0.02399800 -0.04166000 0.07946200
|
| 318 |
+
v 0.02399800 -0.04166000 0.07946200
|
| 319 |
+
v 0.02399800 -0.04166000 0.07946200
|
| 320 |
+
v 0.04200800 -0.02308900 0.07948800
|
| 321 |
+
v 0.04200800 -0.02308900 0.07948800
|
| 322 |
+
v 0.04200800 -0.02308900 0.07948800
|
| 323 |
+
v 0.04200800 -0.02308900 0.07948800
|
| 324 |
+
v 0.04200800 -0.02308900 0.07948800
|
| 325 |
+
v 0.04485500 -0.01674000 0.07943100
|
| 326 |
+
v 0.04485500 -0.01674000 0.07943100
|
| 327 |
+
v 0.04485500 -0.01674000 0.07943100
|
| 328 |
+
v 0.04485500 -0.01674000 0.07943100
|
| 329 |
+
v 0.04485500 -0.01674000 0.07943100
|
| 330 |
+
v 0.04677300 0.00919500 0.07947100
|
| 331 |
+
v 0.04677300 0.00919500 0.07947100
|
| 332 |
+
v 0.04677300 0.00919500 0.07947100
|
| 333 |
+
v 0.04677300 0.00919500 0.07947100
|
| 334 |
+
v 0.04677300 0.00919500 0.07947100
|
| 335 |
+
v 0.04768500 0.00266800 0.07935500
|
| 336 |
+
v 0.04768500 0.00266800 0.07935500
|
| 337 |
+
v 0.04768500 0.00266800 0.07935500
|
| 338 |
+
v 0.04768500 0.00266800 0.07935500
|
| 339 |
+
v 0.04768500 0.00266800 0.07935500
|
| 340 |
+
v 0.04768500 0.00266800 0.07935500
|
| 341 |
+
v 0.04768500 0.00266800 0.07935500
|
| 342 |
+
v 0.04481300 0.01603400 0.07946300
|
| 343 |
+
v 0.04481300 0.01603400 0.07946300
|
| 344 |
+
v 0.04481300 0.01603400 0.07946300
|
| 345 |
+
v 0.04481300 0.01603400 0.07946300
|
| 346 |
+
v 0.04481300 0.01603400 0.07946300
|
| 347 |
+
v 0.04481300 0.01603400 0.07946300
|
| 348 |
+
v 0.02965600 0.03701600 0.07948700
|
| 349 |
+
v 0.02965600 0.03701600 0.07948700
|
| 350 |
+
v 0.02965600 0.03701600 0.07948700
|
| 351 |
+
v 0.02965600 0.03701600 0.07948700
|
| 352 |
+
v 0.02965600 0.03701600 0.07948700
|
| 353 |
+
v 0.02965600 0.03701600 0.07948700
|
| 354 |
+
v 0.02389600 0.04092800 0.07943000
|
| 355 |
+
v 0.02389600 0.04092800 0.07943000
|
| 356 |
+
v 0.02389600 0.04092800 0.07943000
|
| 357 |
+
v 0.02389600 0.04092800 0.07943000
|
| 358 |
+
v 0.02389600 0.04092800 0.07943000
|
| 359 |
+
v -0.00130400 0.04732800 0.07947500
|
| 360 |
+
v -0.00130400 0.04732800 0.07947500
|
| 361 |
+
v -0.00130400 0.04732800 0.07947500
|
| 362 |
+
v -0.00130400 0.04732800 0.07947500
|
| 363 |
+
v -0.00130400 0.04732800 0.07947500
|
| 364 |
+
v -0.00130400 0.04732800 0.07947500
|
| 365 |
+
v -0.00836500 0.04659200 0.07946400
|
| 366 |
+
v -0.00836500 0.04659200 0.07946400
|
| 367 |
+
v -0.00836500 0.04659200 0.07946400
|
| 368 |
+
v -0.00836500 0.04659200 0.07946400
|
| 369 |
+
v -0.00836500 0.04659200 0.07946400
|
| 370 |
+
v -0.03167900 0.03531900 0.07948600
|
| 371 |
+
v -0.03167900 0.03531900 0.07948600
|
| 372 |
+
v -0.03167900 0.03531900 0.07948600
|
| 373 |
+
v -0.03167900 0.03531900 0.07948600
|
| 374 |
+
v -0.03167900 0.03531900 0.07948600
|
| 375 |
+
v -0.03167900 0.03531900 0.07948600
|
| 376 |
+
v -0.03654100 0.03032100 0.07942800
|
| 377 |
+
v -0.03654100 0.03032100 0.07942800
|
| 378 |
+
v -0.03654100 0.03032100 0.07942800
|
| 379 |
+
v -0.03654100 0.03032100 0.07942800
|
| 380 |
+
v -0.03654100 0.03032100 0.07942800
|
| 381 |
+
v -0.04723800 0.00652600 0.07948800
|
| 382 |
+
v -0.04723800 0.00652600 0.07948800
|
| 383 |
+
v -0.04723800 0.00652600 0.07948800
|
| 384 |
+
v -0.04723800 0.00652600 0.07948800
|
| 385 |
+
v -0.04723800 0.00652600 0.07948800
|
| 386 |
+
v -0.04723800 0.00652600 0.07948800
|
| 387 |
+
v 0.01656700 -0.03658200 0.08787600
|
| 388 |
+
v 0.01656700 -0.03658200 0.08787600
|
| 389 |
+
v 0.01656700 -0.03658200 0.08787600
|
| 390 |
+
v 0.01656700 -0.03658200 0.08787600
|
| 391 |
+
v 0.01656700 -0.03658200 0.08787600
|
| 392 |
+
v 0.01656700 -0.03658200 0.08787600
|
| 393 |
+
v 0.01656700 -0.03658200 0.08787600
|
| 394 |
+
v 0.00770400 -0.03840900 0.08895100
|
| 395 |
+
v 0.00770400 -0.03840900 0.08895100
|
| 396 |
+
v 0.00770400 -0.03840900 0.08895100
|
| 397 |
+
v 0.00770400 -0.03840900 0.08895100
|
| 398 |
+
v 0.00770400 -0.03840900 0.08895100
|
| 399 |
+
v 0.00770400 -0.03840900 0.08895100
|
| 400 |
+
v -0.00226300 -0.04008200 0.08792600
|
| 401 |
+
v -0.00226300 -0.04008200 0.08792600
|
| 402 |
+
v -0.00226300 -0.04008200 0.08792600
|
| 403 |
+
v -0.00226300 -0.04008200 0.08792600
|
| 404 |
+
v -0.00226300 -0.04008200 0.08792600
|
| 405 |
+
v -0.00226300 -0.04008200 0.08792600
|
| 406 |
+
v -0.00226300 -0.04008200 0.08792600
|
| 407 |
+
v -0.00226300 -0.04008200 0.08792600
|
| 408 |
+
v -0.00986900 -0.03784800 0.08907500
|
| 409 |
+
v -0.00986900 -0.03784800 0.08907500
|
| 410 |
+
v -0.00986900 -0.03784800 0.08907500
|
| 411 |
+
v -0.00986900 -0.03784800 0.08907500
|
| 412 |
+
v -0.00986900 -0.03784800 0.08907500
|
| 413 |
+
v -0.01875300 -0.03556100 0.08780300
|
| 414 |
+
v -0.01875300 -0.03556100 0.08780300
|
| 415 |
+
v -0.01875300 -0.03556100 0.08780300
|
| 416 |
+
v -0.01875300 -0.03556100 0.08780300
|
| 417 |
+
v -0.01875300 -0.03556100 0.08780300
|
| 418 |
+
v -0.01875300 -0.03556100 0.08780300
|
| 419 |
+
v -0.01875300 -0.03556100 0.08780300
|
| 420 |
+
v -0.01875300 -0.03556100 0.08780300
|
| 421 |
+
v -0.01875300 -0.03556100 0.08780300
|
| 422 |
+
v -0.02843700 -0.02824100 0.08787500
|
| 423 |
+
v -0.02843700 -0.02824100 0.08787500
|
| 424 |
+
v -0.02843700 -0.02824100 0.08787500
|
| 425 |
+
v -0.02843700 -0.02824100 0.08787500
|
| 426 |
+
v -0.02843700 -0.02824100 0.08787500
|
| 427 |
+
v -0.02843700 -0.02824100 0.08787500
|
| 428 |
+
v -0.02843700 -0.02824100 0.08787500
|
| 429 |
+
v 0.02678100 -0.02990400 0.08780900
|
| 430 |
+
v 0.02678100 -0.02990400 0.08780900
|
| 431 |
+
v 0.02678100 -0.02990400 0.08780900
|
| 432 |
+
v 0.02678100 -0.02990400 0.08780900
|
| 433 |
+
v 0.02678100 -0.02990400 0.08780900
|
| 434 |
+
v 0.02678100 -0.02990400 0.08780900
|
| 435 |
+
v 0.02678100 -0.02990400 0.08780900
|
| 436 |
+
v 0.02678100 -0.02990400 0.08780900
|
| 437 |
+
v 0.02678100 -0.02990400 0.08780900
|
| 438 |
+
v 0.03186200 -0.02241000 0.08907400
|
| 439 |
+
v 0.03186200 -0.02241000 0.08907400
|
| 440 |
+
v 0.03186200 -0.02241000 0.08907400
|
| 441 |
+
v 0.03186200 -0.02241000 0.08907400
|
| 442 |
+
v 0.03186200 -0.02241000 0.08907400
|
| 443 |
+
v 0.03575800 -0.01574000 0.08888600
|
| 444 |
+
v 0.03575800 -0.01574000 0.08888600
|
| 445 |
+
v 0.03575800 -0.01574000 0.08888600
|
| 446 |
+
v 0.03575800 -0.01574000 0.08888600
|
| 447 |
+
v 0.03575800 -0.01574000 0.08888600
|
| 448 |
+
v 0.03575800 -0.01574000 0.08888600
|
| 449 |
+
v 0.03575800 -0.01574000 0.08888600
|
| 450 |
+
v 0.03575800 -0.01574000 0.08888600
|
| 451 |
+
v 0.03957100 -0.00392800 0.08797800
|
| 452 |
+
v 0.03957100 -0.00392800 0.08797800
|
| 453 |
+
v 0.03957100 -0.00392800 0.08797800
|
| 454 |
+
v 0.03957100 -0.00392800 0.08797800
|
| 455 |
+
v 0.03957100 -0.00392800 0.08797800
|
| 456 |
+
v 0.03957100 -0.00392800 0.08797800
|
| 457 |
+
v 0.03957100 -0.00392800 0.08797800
|
| 458 |
+
v 0.03957100 -0.00392800 0.08797800
|
| 459 |
+
v 0.03869500 0.00902900 0.08783300
|
| 460 |
+
v 0.03869500 0.00902900 0.08783300
|
| 461 |
+
v 0.03869500 0.00902900 0.08783300
|
| 462 |
+
v 0.03869500 0.00902900 0.08783300
|
| 463 |
+
v 0.03869500 0.00902900 0.08783300
|
| 464 |
+
v 0.03869500 0.00902900 0.08783300
|
| 465 |
+
v 0.03869500 0.00902900 0.08783300
|
| 466 |
+
v 0.00137100 0.03935400 0.08775000
|
| 467 |
+
v 0.00137100 0.03935400 0.08775000
|
| 468 |
+
v 0.00137100 0.03935400 0.08775000
|
| 469 |
+
v 0.00137100 0.03935400 0.08775000
|
| 470 |
+
v 0.00137100 0.03935400 0.08775000
|
| 471 |
+
v 0.00137100 0.03935400 0.08775000
|
| 472 |
+
v 0.01058300 0.03785800 0.08806400
|
| 473 |
+
v 0.01058300 0.03785800 0.08806400
|
| 474 |
+
v 0.01058300 0.03785800 0.08806400
|
| 475 |
+
v 0.01058300 0.03785800 0.08806400
|
| 476 |
+
v 0.01058300 0.03785800 0.08806400
|
| 477 |
+
v 0.01058300 0.03785800 0.08806400
|
| 478 |
+
v 0.01058300 0.03785800 0.08806400
|
| 479 |
+
v 0.01822600 0.03383400 0.08894800
|
| 480 |
+
v 0.01822600 0.03383400 0.08894800
|
| 481 |
+
v 0.01822600 0.03383400 0.08894800
|
| 482 |
+
v 0.01822600 0.03383400 0.08894800
|
| 483 |
+
v 0.01822600 0.03383400 0.08894800
|
| 484 |
+
v 0.01822600 0.03383400 0.08894800
|
| 485 |
+
v 0.01822600 0.03383400 0.08894800
|
| 486 |
+
v 0.02698600 0.02889200 0.08781600
|
| 487 |
+
v 0.02698600 0.02889200 0.08781600
|
| 488 |
+
v 0.02698600 0.02889200 0.08781600
|
| 489 |
+
v 0.02698600 0.02889200 0.08781600
|
| 490 |
+
v 0.02698600 0.02889200 0.08781600
|
| 491 |
+
v 0.02698600 0.02889200 0.08781600
|
| 492 |
+
v 0.02698600 0.02889200 0.08781600
|
| 493 |
+
v 0.03343800 0.01949200 0.08889700
|
| 494 |
+
v 0.03343800 0.01949200 0.08889700
|
| 495 |
+
v 0.03343800 0.01949200 0.08889700
|
| 496 |
+
v 0.03343800 0.01949200 0.08889700
|
| 497 |
+
v 0.03343800 0.01949200 0.08889700
|
| 498 |
+
v 0.03343800 0.01949200 0.08889700
|
| 499 |
+
v 0.03343800 0.01949200 0.08889700
|
| 500 |
+
v 0.03343800 0.01949200 0.08889700
|
| 501 |
+
v -0.03236600 0.02246700 0.08815300
|
| 502 |
+
v -0.03236600 0.02246700 0.08815300
|
| 503 |
+
v -0.03236600 0.02246700 0.08815300
|
| 504 |
+
v -0.03236600 0.02246700 0.08815300
|
| 505 |
+
v -0.03236600 0.02246700 0.08815300
|
| 506 |
+
v -0.03236600 0.02246700 0.08815300
|
| 507 |
+
v -0.03236600 0.02246700 0.08815300
|
| 508 |
+
v -0.03236600 0.02246700 0.08815300
|
| 509 |
+
v -0.02612800 0.02825700 0.08896000
|
| 510 |
+
v -0.02612800 0.02825700 0.08896000
|
| 511 |
+
v -0.02612800 0.02825700 0.08896000
|
| 512 |
+
v -0.02612800 0.02825700 0.08896000
|
| 513 |
+
v -0.02612800 0.02825700 0.08896000
|
| 514 |
+
v -0.02612800 0.02825700 0.08896000
|
| 515 |
+
v -0.01848100 0.03489300 0.08780100
|
| 516 |
+
v -0.01848100 0.03489300 0.08780100
|
| 517 |
+
v -0.01848100 0.03489300 0.08780100
|
| 518 |
+
v -0.01848100 0.03489300 0.08780100
|
| 519 |
+
v -0.01848100 0.03489300 0.08780100
|
| 520 |
+
v -0.01848100 0.03489300 0.08780100
|
| 521 |
+
v -0.01848100 0.03489300 0.08780100
|
| 522 |
+
v -0.01848100 0.03489300 0.08780100
|
| 523 |
+
v -0.00742700 0.03876500 0.08774800
|
| 524 |
+
v -0.00742700 0.03876500 0.08774800
|
| 525 |
+
v -0.00742700 0.03876500 0.08774800
|
| 526 |
+
v -0.00742700 0.03876500 0.08774800
|
| 527 |
+
v -0.00742700 0.03876500 0.08774800
|
| 528 |
+
v -0.00742700 0.03876500 0.08774800
|
| 529 |
+
v -0.00742700 0.03876500 0.08774800
|
| 530 |
+
v -0.00742700 0.03876500 0.08774800
|
| 531 |
+
v -0.03312900 -0.02055500 0.08896000
|
| 532 |
+
v -0.03312900 -0.02055500 0.08896000
|
| 533 |
+
v -0.03312900 -0.02055500 0.08896000
|
| 534 |
+
v -0.03312900 -0.02055500 0.08896000
|
| 535 |
+
v -0.03312900 -0.02055500 0.08896000
|
| 536 |
+
v -0.03312900 -0.02055500 0.08896000
|
| 537 |
+
v -0.03815500 -0.01183500 0.08781000
|
| 538 |
+
v -0.03815500 -0.01183500 0.08781000
|
| 539 |
+
v -0.03815500 -0.01183500 0.08781000
|
| 540 |
+
v -0.03815500 -0.01183500 0.08781000
|
| 541 |
+
v -0.03815500 -0.01183500 0.08781000
|
| 542 |
+
v -0.03815500 -0.01183500 0.08781000
|
| 543 |
+
v -0.03815500 -0.01183500 0.08781000
|
| 544 |
+
v -0.03815500 -0.01183500 0.08781000
|
| 545 |
+
v -0.03891800 0.00032400 0.08885400
|
| 546 |
+
v -0.03891800 0.00032400 0.08885400
|
| 547 |
+
v -0.03891800 0.00032400 0.08885400
|
| 548 |
+
v -0.03891800 0.00032400 0.08885400
|
| 549 |
+
v -0.03891800 0.00032400 0.08885400
|
| 550 |
+
v -0.03891800 0.00032400 0.08885400
|
| 551 |
+
v -0.03891800 0.00032400 0.08885400
|
| 552 |
+
v -0.03820300 0.01119100 0.08770700
|
| 553 |
+
v -0.03820300 0.01119100 0.08770700
|
| 554 |
+
v -0.03820300 0.01119100 0.08770700
|
| 555 |
+
v -0.03820300 0.01119100 0.08770700
|
| 556 |
+
v -0.03820300 0.01119100 0.08770700
|
| 557 |
+
v -0.03820300 0.01119100 0.08770700
|
| 558 |
+
v -0.03820300 0.01119100 0.08770700
|
| 559 |
+
v -0.03820300 0.01119100 0.08770700
|
| 560 |
+
v 0.03607400 -0.00676100 0.33908800
|
| 561 |
+
v 0.03607400 -0.00676100 0.33908800
|
| 562 |
+
v 0.03663100 -0.00040000 0.33908800
|
| 563 |
+
v 0.03663100 -0.00040000 0.33908800
|
| 564 |
+
v 0.03663100 -0.00040000 0.33908800
|
| 565 |
+
v 0.03442100 -0.01292800 0.33908800
|
| 566 |
+
v 0.03442100 -0.01292800 0.33908800
|
| 567 |
+
v 0.03442100 -0.01292800 0.33908800
|
| 568 |
+
v 0.03172300 -0.01871500 0.33908800
|
| 569 |
+
v 0.03172300 -0.01871500 0.33908800
|
| 570 |
+
v 0.02806100 -0.02394600 0.33908800
|
| 571 |
+
v 0.01831500 -0.03212300 0.33908800
|
| 572 |
+
v 0.02354600 -0.02846100 0.33908800
|
| 573 |
+
v 0.01252800 -0.03482100 0.33908800
|
| 574 |
+
v 0.01252800 -0.03482100 0.33908800
|
| 575 |
+
v 0.00636100 -0.03647400 0.33908800
|
| 576 |
+
v 0.00636100 -0.03647400 0.33908800
|
| 577 |
+
v 0.00000000 -0.03703100 0.33908800
|
| 578 |
+
v 0.00000000 -0.03703100 0.33908800
|
| 579 |
+
v 0.00000000 -0.03703100 0.33908800
|
| 580 |
+
v -0.00636100 -0.03647400 0.33908800
|
| 581 |
+
v -0.01252800 -0.03482200 0.33908800
|
| 582 |
+
v -0.01831500 -0.03212300 0.33908800
|
| 583 |
+
v -0.02354600 -0.02846100 0.33908800
|
| 584 |
+
v -0.03172300 -0.01871500 0.33908800
|
| 585 |
+
v -0.03172300 -0.01871500 0.33908800
|
| 586 |
+
v -0.02806100 -0.02394600 0.33908800
|
| 587 |
+
v -0.02806100 -0.02394600 0.33908800
|
| 588 |
+
v -0.03442100 -0.01292800 0.33908800
|
| 589 |
+
v -0.03442100 -0.01292800 0.33908800
|
| 590 |
+
v -0.03442100 -0.01292800 0.33908800
|
| 591 |
+
v -0.03607400 -0.00676100 0.33908800
|
| 592 |
+
v -0.03607400 -0.00676100 0.33908800
|
| 593 |
+
v -0.03663100 -0.00040000 0.33908800
|
| 594 |
+
v -0.03663100 -0.00040000 0.33908800
|
| 595 |
+
v -0.03663100 -0.00040000 0.33908800
|
| 596 |
+
v -0.03607400 0.00596100 0.33908800
|
| 597 |
+
v -0.03607400 0.00596100 0.33908800
|
| 598 |
+
v -0.03442200 0.01212800 0.33908800
|
| 599 |
+
v -0.03442200 0.01212800 0.33908800
|
| 600 |
+
v -0.03442200 0.01212800 0.33908800
|
| 601 |
+
v -0.03172300 0.01791500 0.33908800
|
| 602 |
+
v -0.03172300 0.01791500 0.33908800
|
| 603 |
+
v -0.02806100 0.02314600 0.33908800
|
| 604 |
+
v -0.02806100 0.02314600 0.33908800
|
| 605 |
+
v -0.02806100 0.02314600 0.33908800
|
| 606 |
+
v -0.01831500 0.03132300 0.33908800
|
| 607 |
+
v -0.01831500 0.03132300 0.33908800
|
| 608 |
+
v -0.02354600 0.02766100 0.33908800
|
| 609 |
+
v -0.02354600 0.02766100 0.33908800
|
| 610 |
+
v -0.01252800 0.03402100 0.33908800
|
| 611 |
+
v -0.00636100 0.03567400 0.33908800
|
| 612 |
+
v -0.00636100 0.03567400 0.33908800
|
| 613 |
+
v -0.00636100 0.03567400 0.33908800
|
| 614 |
+
v -0.00000000 0.03623100 0.33908800
|
| 615 |
+
v -0.00000000 0.03623100 0.33908800
|
| 616 |
+
v 0.00636100 0.03567400 0.33908800
|
| 617 |
+
v 0.00636100 0.03567400 0.33908800
|
| 618 |
+
v 0.01268000 0.03398400 0.33908800
|
| 619 |
+
v 0.01268000 0.03398400 0.33908800
|
| 620 |
+
v 0.01268000 0.03398400 0.33908800
|
| 621 |
+
v 0.01268000 0.03398400 0.33908800
|
| 622 |
+
v 0.01831500 0.03132300 0.33908800
|
| 623 |
+
v 0.01831500 0.03132300 0.33908800
|
| 624 |
+
v 0.02354600 0.02766100 0.33908800
|
| 625 |
+
v 0.02354600 0.02766100 0.33908800
|
| 626 |
+
v 0.03172300 0.01791500 0.33908800
|
| 627 |
+
v 0.02806100 0.02314600 0.33908800
|
| 628 |
+
v 0.03442100 0.01212800 0.33908800
|
| 629 |
+
v 0.03607400 0.00596100 0.33908800
|
| 630 |
+
v 0.03233600 0.01896300 0.09291600
|
| 631 |
+
v 0.03233600 0.01896300 0.09291600
|
| 632 |
+
v 0.03233600 0.01896300 0.09291600
|
| 633 |
+
v 0.03233600 0.01896300 0.09291600
|
| 634 |
+
v 0.03233600 0.01896300 0.09291600
|
| 635 |
+
v -0.00407800 0.03706400 0.09159000
|
| 636 |
+
v -0.00407800 0.03706400 0.09159000
|
| 637 |
+
v -0.00407800 0.03706400 0.09159000
|
| 638 |
+
v -0.00407800 0.03706400 0.09159000
|
| 639 |
+
v -0.00407800 0.03706400 0.09159000
|
| 640 |
+
v -0.03670500 0.00827100 0.09150300
|
| 641 |
+
v -0.03670500 0.00827100 0.09150300
|
| 642 |
+
v -0.03670500 0.00827100 0.09150300
|
| 643 |
+
v -0.03670500 0.00827100 0.09150300
|
| 644 |
+
v -0.03670500 0.00827100 0.09150300
|
| 645 |
+
v -0.03777700 -0.00079800 0.09166700
|
| 646 |
+
v -0.03777700 -0.00079800 0.09166700
|
| 647 |
+
v -0.03777700 -0.00079800 0.09166700
|
| 648 |
+
v -0.03777700 -0.00079800 0.09166700
|
| 649 |
+
v -0.03777700 -0.00079800 0.09166700
|
| 650 |
+
v -0.03777700 -0.00079800 0.09166700
|
| 651 |
+
v -0.02068000 -0.03190400 0.09159100
|
| 652 |
+
v -0.02068000 -0.03190400 0.09159100
|
| 653 |
+
v -0.02068000 -0.03190400 0.09159100
|
| 654 |
+
v -0.02068000 -0.03190400 0.09159100
|
| 655 |
+
v -0.01552700 -0.03477100 0.09150400
|
| 656 |
+
v -0.01552700 -0.03477100 0.09150400
|
| 657 |
+
v -0.01552700 -0.03477100 0.09150400
|
| 658 |
+
v -0.01552700 -0.03477100 0.09150400
|
| 659 |
+
v -0.01552700 -0.03477100 0.09150400
|
| 660 |
+
v -0.01552700 -0.03477100 0.09150400
|
| 661 |
+
v 0.02720500 -0.02647100 0.09159300
|
| 662 |
+
v 0.02720500 -0.02647100 0.09159300
|
| 663 |
+
v 0.02720500 -0.02647100 0.09159300
|
| 664 |
+
v 0.02720500 -0.02647100 0.09159300
|
| 665 |
+
v 0.02720500 -0.02647100 0.09159300
|
| 666 |
+
v 0.02720500 -0.02647100 0.09159300
|
| 667 |
+
v 0.02281200 -0.03043400 0.09150300
|
| 668 |
+
v 0.02281200 -0.03043400 0.09150300
|
| 669 |
+
v 0.02281200 -0.03043400 0.09150300
|
| 670 |
+
v 0.02281200 -0.03043400 0.09150300
|
| 671 |
+
v 0.03772800 0.00261600 0.09145400
|
| 672 |
+
v 0.03772800 0.00261600 0.09145400
|
| 673 |
+
v 0.03772800 0.00261600 0.09145400
|
| 674 |
+
v 0.03772800 0.00261600 0.09145400
|
| 675 |
+
v 0.03772800 0.00261600 0.09145400
|
| 676 |
+
v 0.03772800 0.00261600 0.09145400
|
| 677 |
+
v 0.03720900 -0.00626800 0.09162600
|
| 678 |
+
v 0.03720900 -0.00626800 0.09162600
|
| 679 |
+
v 0.03720900 -0.00626800 0.09162600
|
| 680 |
+
v 0.03720900 -0.00626800 0.09162600
|
| 681 |
+
v 0.03720900 -0.00626800 0.09162600
|
| 682 |
+
v 0.03591700 -0.01178600 0.09159900
|
| 683 |
+
v 0.03591700 -0.01178600 0.09159900
|
| 684 |
+
v 0.03591700 -0.01178600 0.09159900
|
| 685 |
+
v 0.03591700 -0.01178600 0.09159900
|
| 686 |
+
v 0.03591700 -0.01178600 0.09159900
|
| 687 |
+
v 0.03220100 -0.01989100 0.09312000
|
| 688 |
+
v 0.03220100 -0.01989100 0.09312000
|
| 689 |
+
v 0.03220100 -0.01989100 0.09312000
|
| 690 |
+
v 0.03220100 -0.01989100 0.09312000
|
| 691 |
+
v 0.03220100 -0.01989100 0.09312000
|
| 692 |
+
v 0.03220100 -0.01989100 0.09312000
|
| 693 |
+
v 0.01782800 -0.03359900 0.09159300
|
| 694 |
+
v 0.01782800 -0.03359900 0.09159300
|
| 695 |
+
v 0.01782800 -0.03359900 0.09159300
|
| 696 |
+
v 0.01782800 -0.03359900 0.09159300
|
| 697 |
+
v 0.01782800 -0.03359900 0.09159300
|
| 698 |
+
v 0.01782800 -0.03359900 0.09159300
|
| 699 |
+
v 0.01033900 -0.03679700 0.09153300
|
| 700 |
+
v 0.01033900 -0.03679700 0.09153300
|
| 701 |
+
v 0.01033900 -0.03679700 0.09153300
|
| 702 |
+
v 0.01033900 -0.03679700 0.09153300
|
| 703 |
+
v 0.01033900 -0.03679700 0.09153300
|
| 704 |
+
v 0.01033900 -0.03679700 0.09153300
|
| 705 |
+
v 0.00121700 -0.03806600 0.09158700
|
| 706 |
+
v 0.00121700 -0.03806600 0.09158700
|
| 707 |
+
v 0.00121700 -0.03806600 0.09158700
|
| 708 |
+
v 0.00121700 -0.03806600 0.09158700
|
| 709 |
+
v 0.00121700 -0.03806600 0.09158700
|
| 710 |
+
v -0.00710100 -0.03746900 0.09178700
|
| 711 |
+
v -0.00710100 -0.03746900 0.09178700
|
| 712 |
+
v -0.00710100 -0.03746900 0.09178700
|
| 713 |
+
v -0.00710100 -0.03746900 0.09178700
|
| 714 |
+
v -0.00710100 -0.03746900 0.09178700
|
| 715 |
+
v -0.00710100 -0.03746900 0.09178700
|
| 716 |
+
v -0.02522400 -0.02839700 0.09159200
|
| 717 |
+
v -0.02522400 -0.02839700 0.09159200
|
| 718 |
+
v -0.02522400 -0.02839700 0.09159200
|
| 719 |
+
v -0.02522400 -0.02839700 0.09159200
|
| 720 |
+
v -0.02522400 -0.02839700 0.09159200
|
| 721 |
+
v -0.02522400 -0.02839700 0.09159200
|
| 722 |
+
v -0.03076300 -0.02243000 0.09153300
|
| 723 |
+
v -0.03076300 -0.02243000 0.09153300
|
| 724 |
+
v -0.03076300 -0.02243000 0.09153300
|
| 725 |
+
v -0.03076300 -0.02243000 0.09153300
|
| 726 |
+
v -0.03076300 -0.02243000 0.09153300
|
| 727 |
+
v -0.03076300 -0.02243000 0.09153300
|
| 728 |
+
v -0.03495700 -0.01445800 0.09160000
|
| 729 |
+
v -0.03495700 -0.01445800 0.09160000
|
| 730 |
+
v -0.03495700 -0.01445800 0.09160000
|
| 731 |
+
v -0.03495700 -0.01445800 0.09160000
|
| 732 |
+
v -0.03495700 -0.01445800 0.09160000
|
| 733 |
+
v -0.03676700 -0.00881000 0.09150300
|
| 734 |
+
v -0.03676700 -0.00881000 0.09150300
|
| 735 |
+
v -0.03676700 -0.00881000 0.09150300
|
| 736 |
+
v -0.03676700 -0.00881000 0.09150300
|
| 737 |
+
v -0.03676700 -0.00881000 0.09150300
|
| 738 |
+
v -0.03224600 0.01914100 0.09154100
|
| 739 |
+
v -0.03224600 0.01914100 0.09154100
|
| 740 |
+
v -0.03224600 0.01914100 0.09154100
|
| 741 |
+
v -0.03224600 0.01914100 0.09154100
|
| 742 |
+
v -0.03224600 0.01914100 0.09154100
|
| 743 |
+
v -0.02726300 0.02571200 0.09178100
|
| 744 |
+
v -0.02726300 0.02571200 0.09178100
|
| 745 |
+
v -0.02726300 0.02571200 0.09178100
|
| 746 |
+
v -0.02726300 0.02571200 0.09178100
|
| 747 |
+
v -0.02726300 0.02571200 0.09178100
|
| 748 |
+
v -0.02726300 0.02571200 0.09178100
|
| 749 |
+
v -0.02047400 0.03123000 0.09159900
|
| 750 |
+
v -0.02047400 0.03123000 0.09159900
|
| 751 |
+
v -0.02047400 0.03123000 0.09159900
|
| 752 |
+
v -0.02047400 0.03123000 0.09159900
|
| 753 |
+
v -0.02047400 0.03123000 0.09159900
|
| 754 |
+
v -0.01543000 0.03397500 0.09159700
|
| 755 |
+
v -0.01543000 0.03397500 0.09159700
|
| 756 |
+
v -0.01543000 0.03397500 0.09159700
|
| 757 |
+
v -0.01543000 0.03397500 0.09159700
|
| 758 |
+
v -0.01543000 0.03397500 0.09159700
|
| 759 |
+
v 0.00749100 0.03655300 0.09154100
|
| 760 |
+
v 0.00749100 0.03655300 0.09154100
|
| 761 |
+
v 0.00749100 0.03655300 0.09154100
|
| 762 |
+
v 0.00749100 0.03655300 0.09154100
|
| 763 |
+
v 0.00749100 0.03655300 0.09154100
|
| 764 |
+
v 0.01535000 0.03409100 0.09177300
|
| 765 |
+
v 0.01535000 0.03409100 0.09177300
|
| 766 |
+
v 0.01535000 0.03409100 0.09177300
|
| 767 |
+
v 0.01535000 0.03409100 0.09177300
|
| 768 |
+
v 0.01535000 0.03409100 0.09177300
|
| 769 |
+
v 0.01535000 0.03409100 0.09177300
|
| 770 |
+
v 0.01535000 0.03409100 0.09177300
|
| 771 |
+
v 0.02285200 0.02955800 0.09159900
|
| 772 |
+
v 0.02285200 0.02955800 0.09159900
|
| 773 |
+
v 0.02285200 0.02955800 0.09159900
|
| 774 |
+
v 0.02285200 0.02955800 0.09159900
|
| 775 |
+
v 0.02285200 0.02955800 0.09159900
|
| 776 |
+
v 0.02729100 0.02563300 0.09150300
|
| 777 |
+
v 0.02729100 0.02563300 0.09150300
|
| 778 |
+
v 0.02729100 0.02563300 0.09150300
|
| 779 |
+
v 0.02729100 0.02563300 0.09150300
|
| 780 |
+
v 0.02729100 0.02563300 0.09150300
|
| 781 |
+
v 0.02729100 0.02563300 0.09150300
|
| 782 |
+
v -0.03487300 0.01388100 0.09159200
|
| 783 |
+
v -0.03487300 0.01388100 0.09159200
|
| 784 |
+
v -0.03487300 0.01388100 0.09159200
|
| 785 |
+
v -0.03487300 0.01388100 0.09159200
|
| 786 |
+
v -0.03487300 0.01388100 0.09159200
|
| 787 |
+
v -0.00987500 0.03600000 0.09150400
|
| 788 |
+
v -0.00987500 0.03600000 0.09150400
|
| 789 |
+
v -0.00987500 0.03600000 0.09150400
|
| 790 |
+
v -0.00987500 0.03600000 0.09150400
|
| 791 |
+
v -0.00987500 0.03600000 0.09150400
|
| 792 |
+
v 0.00165900 0.03724700 0.09159200
|
| 793 |
+
v 0.00165900 0.03724700 0.09159200
|
| 794 |
+
v 0.00165900 0.03724700 0.09159200
|
| 795 |
+
v 0.00165900 0.03724700 0.09159200
|
| 796 |
+
v 0.00165900 0.03724700 0.09159200
|
| 797 |
+
v 0.03597500 0.01092400 0.09150300
|
| 798 |
+
v 0.03597500 0.01092400 0.09150300
|
| 799 |
+
v 0.03597500 0.01092400 0.09150300
|
| 800 |
+
v 0.03597500 0.01092400 0.09150300
|
| 801 |
+
v 0.03597500 0.01092400 0.09150300
|
| 802 |
+
v 0.03080600 -0.02200000 0.33908800
|
| 803 |
+
v 0.03080600 -0.02200000 0.33908800
|
| 804 |
+
v 0.03080600 -0.02200000 0.33908800
|
| 805 |
+
v 0.03080600 -0.02200000 0.33908800
|
| 806 |
+
v 0.03080600 -0.02200000 0.33908800
|
| 807 |
+
v 0.03080600 -0.02200000 0.33908800
|
| 808 |
+
v 0.03625600 -0.01050600 0.33908800
|
| 809 |
+
v 0.03625600 -0.01050600 0.33908800
|
| 810 |
+
v 0.03625600 -0.01050600 0.33908800
|
| 811 |
+
v 0.03625600 -0.01050600 0.33908800
|
| 812 |
+
v 0.03625600 -0.01050600 0.33908800
|
| 813 |
+
v 0.03625600 -0.01050600 0.33908800
|
| 814 |
+
v 0.03625600 -0.01050600 0.33908800
|
| 815 |
+
v 0.03625600 -0.01050600 0.33908800
|
| 816 |
+
v 0.03750000 -0.00040000 0.33908800
|
| 817 |
+
v 0.03750000 -0.00040000 0.33908800
|
| 818 |
+
v 0.03750000 -0.00040000 0.33908800
|
| 819 |
+
v 0.03750000 -0.00040000 0.33908800
|
| 820 |
+
v 0.03750000 -0.00040000 0.33908800
|
| 821 |
+
v 0.03620800 0.00979700 0.33908800
|
| 822 |
+
v 0.03620800 0.00979700 0.33908800
|
| 823 |
+
v 0.03620800 0.00979700 0.33908800
|
| 824 |
+
v 0.03620800 0.00979700 0.33908800
|
| 825 |
+
v 0.03620800 0.00979700 0.33908800
|
| 826 |
+
v 0.03080600 0.02120000 0.33908800
|
| 827 |
+
v 0.03080600 0.02120000 0.33908800
|
| 828 |
+
v 0.03080600 0.02120000 0.33908800
|
| 829 |
+
v 0.03080600 0.02120000 0.33908800
|
| 830 |
+
v 0.03080600 0.02120000 0.33908800
|
| 831 |
+
v 0.02186600 0.03023400 0.33908800
|
| 832 |
+
v 0.02186600 0.03023400 0.33908800
|
| 833 |
+
v 0.02186600 0.03023400 0.33908800
|
| 834 |
+
v 0.02186600 0.03023400 0.33908800
|
| 835 |
+
v 0.02186600 0.03023400 0.33908800
|
| 836 |
+
v 0.02186600 0.03023400 0.33908800
|
| 837 |
+
v 0.00439000 0.03706200 0.33908800
|
| 838 |
+
v 0.00439000 0.03706200 0.33908800
|
| 839 |
+
v 0.00439000 0.03706200 0.33908800
|
| 840 |
+
v 0.00439000 0.03706200 0.33908800
|
| 841 |
+
v 0.00439000 0.03706200 0.33908800
|
| 842 |
+
v 0.00439000 0.03706200 0.33908800
|
| 843 |
+
v 0.00439000 0.03706200 0.33908800
|
| 844 |
+
v 0.00439000 0.03706200 0.33908800
|
| 845 |
+
v 0.00439000 0.03706200 0.33908800
|
| 846 |
+
v -0.00980700 0.03592300 0.33908800
|
| 847 |
+
v -0.00980700 0.03592300 0.33908800
|
| 848 |
+
v -0.00980700 0.03592300 0.33908800
|
| 849 |
+
v -0.00980700 0.03592300 0.33908800
|
| 850 |
+
v -0.00980700 0.03592300 0.33908800
|
| 851 |
+
v -0.00980700 0.03592300 0.33908800
|
| 852 |
+
v -0.00980700 0.03592300 0.33908800
|
| 853 |
+
v -0.02133900 0.03060300 0.33908800
|
| 854 |
+
v -0.02133900 0.03060300 0.33908800
|
| 855 |
+
v -0.02133900 0.03060300 0.33908800
|
| 856 |
+
v -0.02133900 0.03060300 0.33908800
|
| 857 |
+
v -0.02133900 0.03060300 0.33908800
|
| 858 |
+
v -0.02133900 0.03060300 0.33908800
|
| 859 |
+
v -0.02133900 0.03060300 0.33908800
|
| 860 |
+
v -0.03070300 0.02140900 0.33908800
|
| 861 |
+
v -0.03070300 0.02140900 0.33908800
|
| 862 |
+
v -0.03070300 0.02140900 0.33908800
|
| 863 |
+
v -0.03070300 0.02140900 0.33908800
|
| 864 |
+
v -0.03070300 0.02140900 0.33908800
|
| 865 |
+
v -0.03070300 0.02140900 0.33908800
|
| 866 |
+
v -0.03070300 0.02140900 0.33908800
|
| 867 |
+
v -0.03070300 0.02140900 0.33908800
|
| 868 |
+
v -0.03642700 0.00899900 0.33908800
|
| 869 |
+
v -0.03642700 0.00899900 0.33908800
|
| 870 |
+
v -0.03642700 0.00899900 0.33908800
|
| 871 |
+
v -0.03642700 0.00899900 0.33908800
|
| 872 |
+
v -0.03642700 0.00899900 0.33908800
|
| 873 |
+
v -0.03642700 0.00899900 0.33908800
|
| 874 |
+
v -0.03642700 0.00899900 0.33908800
|
| 875 |
+
v -0.03642700 0.00899900 0.33908800
|
| 876 |
+
v -0.03749100 -0.00356100 0.33908800
|
| 877 |
+
v -0.03749100 -0.00356100 0.33908800
|
| 878 |
+
v -0.03749100 -0.00356100 0.33908800
|
| 879 |
+
v -0.03749100 -0.00356100 0.33908800
|
| 880 |
+
v -0.03749100 -0.00356100 0.33908800
|
| 881 |
+
v -0.03749100 -0.00356100 0.33908800
|
| 882 |
+
v -0.03430100 -0.01589600 0.33908800
|
| 883 |
+
v -0.03430100 -0.01589600 0.33908800
|
| 884 |
+
v -0.03430100 -0.01589600 0.33908800
|
| 885 |
+
v -0.03430100 -0.01589600 0.33908800
|
| 886 |
+
v -0.03430100 -0.01589600 0.33908800
|
| 887 |
+
v -0.03430100 -0.01589600 0.33908800
|
| 888 |
+
v -0.03430100 -0.01589600 0.33908800
|
| 889 |
+
v -0.03430100 -0.01589600 0.33908800
|
| 890 |
+
v -0.02872600 -0.02450400 0.33908800
|
| 891 |
+
v -0.02872600 -0.02450400 0.33908800
|
| 892 |
+
v -0.02872600 -0.02450400 0.33908800
|
| 893 |
+
v -0.02872600 -0.02450400 0.33908800
|
| 894 |
+
v -0.02125400 -0.03144000 0.33908800
|
| 895 |
+
v -0.02125400 -0.03144000 0.33908800
|
| 896 |
+
v -0.02125400 -0.03144000 0.33908800
|
| 897 |
+
v -0.02125400 -0.03144000 0.33908800
|
| 898 |
+
v -0.02125400 -0.03144000 0.33908800
|
| 899 |
+
v -0.00980700 -0.03672300 0.33908800
|
| 900 |
+
v -0.00980700 -0.03672300 0.33908800
|
| 901 |
+
v -0.00980700 -0.03672300 0.33908800
|
| 902 |
+
v -0.00980700 -0.03672300 0.33908800
|
| 903 |
+
v -0.00980700 -0.03672300 0.33908800
|
| 904 |
+
v 0.00290800 -0.03791100 0.33908800
|
| 905 |
+
v 0.00290800 -0.03791100 0.33908800
|
| 906 |
+
v 0.00290800 -0.03791100 0.33908800
|
| 907 |
+
v 0.00290800 -0.03791100 0.33908800
|
| 908 |
+
v 0.00290800 -0.03791100 0.33908800
|
| 909 |
+
v 0.00290800 -0.03791100 0.33908800
|
| 910 |
+
v 0.00290800 -0.03791100 0.33908800
|
| 911 |
+
v 0.00290800 -0.03791100 0.33908800
|
| 912 |
+
v 0.01282600 -0.03563800 0.33908800
|
| 913 |
+
v 0.01282600 -0.03563800 0.33908800
|
| 914 |
+
v 0.01282600 -0.03563800 0.33908800
|
| 915 |
+
v 0.01282600 -0.03563800 0.33908800
|
| 916 |
+
v 0.02193300 -0.03096200 0.33908800
|
| 917 |
+
v 0.02193300 -0.03096200 0.33908800
|
| 918 |
+
v 0.02193300 -0.03096200 0.33908800
|
| 919 |
+
v 0.02193300 -0.03096200 0.33908800
|
| 920 |
+
v 0.02193300 -0.03096200 0.33908800
|
| 921 |
+
vn -0.06210000 0.99800000 0.01260000
|
| 922 |
+
vn 0.04080000 0.99430000 0.09860000
|
| 923 |
+
vn 0.10140000 0.99480000 0.01130000
|
| 924 |
+
vn 0.10140000 0.99480000 0.01130000
|
| 925 |
+
vn 0.23840000 0.95970000 0.14860000
|
| 926 |
+
vn 0.23840000 0.95970000 0.14860000
|
| 927 |
+
vn 0.17950000 0.98240000 -0.05210000
|
| 928 |
+
vn 0.30380000 0.94790000 0.09600000
|
| 929 |
+
vn 0.37440000 0.92710000 0.01760000
|
| 930 |
+
vn 0.49020000 0.87090000 0.03630000
|
| 931 |
+
vn 0.43640000 0.89390000 0.10230000
|
| 932 |
+
vn 0.37440000 0.92710000 0.01760000
|
| 933 |
+
vn 0.59390000 0.80440000 0.01300000
|
| 934 |
+
vn 0.55930000 0.82480000 0.08360000
|
| 935 |
+
vn 0.49020000 0.87090000 0.03630000
|
| 936 |
+
vn 0.59390000 0.80440000 0.01300000
|
| 937 |
+
vn 0.71710000 0.69680000 0.01270000
|
| 938 |
+
vn 0.67010000 0.73560000 0.09940000
|
| 939 |
+
vn 0.71710000 0.69680000 0.01270000
|
| 940 |
+
vn 0.79940000 0.58180000 0.14990000
|
| 941 |
+
vn 0.88260000 0.46940000 0.02580000
|
| 942 |
+
vn 0.84570000 0.52500000 0.09630000
|
| 943 |
+
vn 0.76520000 0.64050000 -0.06550000
|
| 944 |
+
vn 0.79940000 0.58180000 0.14990000
|
| 945 |
+
vn 0.88260000 0.46940000 0.02580000
|
| 946 |
+
vn 0.90720000 0.40750000 0.10410000
|
| 947 |
+
vn 0.93520000 0.35200000 0.03790000
|
| 948 |
+
vn 0.93520000 0.35200000 0.03790000
|
| 949 |
+
vn 0.97200000 0.23450000 0.01200000
|
| 950 |
+
vn 0.95760000 0.27460000 0.08720000
|
| 951 |
+
vn 0.98610000 0.13610000 0.09590000
|
| 952 |
+
vn 0.97200000 0.23450000 0.01200000
|
| 953 |
+
vn 0.99730000 0.07290000 0.00480000
|
| 954 |
+
vn 0.98560000 -0.06810000 0.15490000
|
| 955 |
+
vn 0.99730000 0.07290000 0.00480000
|
| 956 |
+
vn 0.98560000 -0.06810000 0.15490000
|
| 957 |
+
vn 0.97800000 -0.20780000 0.01800000
|
| 958 |
+
vn 0.98640000 -0.13140000 0.09910000
|
| 959 |
+
vn 0.99890000 -0.00860000 -0.04710000
|
| 960 |
+
vn 0.95620000 -0.27410000 0.10240000
|
| 961 |
+
vn 0.97800000 -0.20780000 0.01800000
|
| 962 |
+
vn 0.94270000 -0.33150000 0.03640000
|
| 963 |
+
vn 0.94270000 -0.33150000 0.03640000
|
| 964 |
+
vn 0.89540000 -0.44520000 0.01280000
|
| 965 |
+
vn 0.90950000 -0.40710000 0.08380000
|
| 966 |
+
vn 0.89540000 -0.44520000 0.01280000
|
| 967 |
+
vn 0.81080000 -0.58520000 0.01230000
|
| 968 |
+
vn 0.84110000 -0.53170000 0.09930000
|
| 969 |
+
vn 0.71170000 -0.68610000 0.15110000
|
| 970 |
+
vn 0.81080000 -0.58520000 0.01230000
|
| 971 |
+
vn 0.71170000 -0.68610000 0.15110000
|
| 972 |
+
vn 0.76250000 -0.64440000 -0.05800000
|
| 973 |
+
vn 0.67070000 -0.73550000 0.09600000
|
| 974 |
+
vn 0.61560000 -0.78780000 0.01910000
|
| 975 |
+
vn 0.55850000 -0.82310000 0.10260000
|
| 976 |
+
vn 0.50910000 -0.85990000 0.03770000
|
| 977 |
+
vn 0.61560000 -0.78780000 0.01910000
|
| 978 |
+
vn 0.43720000 -0.89510000 0.08760000
|
| 979 |
+
vn 0.50910000 -0.85990000 0.03770000
|
| 980 |
+
vn 0.39970000 -0.91660000 0.01140000
|
| 981 |
+
vn 0.39970000 -0.91660000 0.01140000
|
| 982 |
+
vn 0.24490000 -0.96950000 0.00470000
|
| 983 |
+
vn 0.30560000 -0.94730000 0.09580000
|
| 984 |
+
vn 0.24490000 -0.96950000 0.00470000
|
| 985 |
+
vn 0.10040000 -0.98210000 0.15960000
|
| 986 |
+
vn 0.10040000 -0.98210000 0.15960000
|
| 987 |
+
vn 0.16440000 -0.98410000 -0.06650000
|
| 988 |
+
vn 0.04230000 -0.99390000 0.10220000
|
| 989 |
+
vn -0.04790000 -0.99860000 0.02460000
|
| 990 |
+
vn -0.04790000 -0.99860000 0.02460000
|
| 991 |
+
vn -0.10340000 -0.98970000 0.09950000
|
| 992 |
+
vn -0.16530000 -0.98550000 0.03780000
|
| 993 |
+
vn -0.24260000 -0.96650000 0.08410000
|
| 994 |
+
vn -0.16530000 -0.98550000 0.03780000
|
| 995 |
+
vn -0.28290000 -0.95910000 0.01260000
|
| 996 |
+
vn -0.43560000 -0.90010000 0.00410000
|
| 997 |
+
vn -0.37330000 -0.92280000 0.09570000
|
| 998 |
+
vn -0.28290000 -0.95910000 0.01260000
|
| 999 |
+
vn -0.55140000 -0.81890000 0.15910000
|
| 1000 |
+
vn -0.43560000 -0.90010000 0.00410000
|
| 1001 |
+
vn -0.60430000 -0.79050000 0.09980000
|
| 1002 |
+
vn -0.50570000 -0.86130000 -0.04920000
|
| 1003 |
+
vn -0.55140000 -0.81890000 0.15910000
|
| 1004 |
+
vn -0.66890000 -0.74310000 0.01920000
|
| 1005 |
+
vn -0.71320000 -0.69340000 0.10240000
|
| 1006 |
+
vn -0.75840000 -0.65070000 0.03750000
|
| 1007 |
+
vn -0.66890000 -0.74310000 0.01920000
|
| 1008 |
+
vn -0.75840000 -0.65070000 0.03750000
|
| 1009 |
+
vn -0.80590000 -0.58530000 0.08880000
|
| 1010 |
+
vn -0.83320000 -0.55280000 0.01350000
|
| 1011 |
+
vn -0.83320000 -0.55280000 0.01350000
|
| 1012 |
+
vn -0.87990000 -0.46540000 0.09520000
|
| 1013 |
+
vn -0.91230000 -0.40960000 0.00460000
|
| 1014 |
+
vn -0.94920000 -0.27310000 0.15660000
|
| 1015 |
+
vn -0.91230000 -0.40960000 0.00460000
|
| 1016 |
+
vn -0.99010000 -0.13930000 0.01850000
|
| 1017 |
+
vn -0.97160000 -0.21490000 0.09940000
|
| 1018 |
+
vn -0.94150000 -0.33380000 -0.04700000
|
| 1019 |
+
vn -0.94920000 -0.27310000 0.15660000
|
| 1020 |
+
vn -0.99220000 -0.07050000 0.10260000
|
| 1021 |
+
vn -0.99010000 -0.13930000 0.01850000
|
| 1022 |
+
vn -0.99930000 -0.01090000 0.03630000
|
| 1023 |
+
vn -0.99360000 0.11210000 0.01240000
|
| 1024 |
+
vn -0.99930000 -0.01090000 0.03630000
|
| 1025 |
+
vn -0.99390000 0.07080000 0.08440000
|
| 1026 |
+
vn -0.96200000 0.27260000 0.01220000
|
| 1027 |
+
vn -0.97240000 0.21130000 0.09930000
|
| 1028 |
+
vn -0.99360000 0.11210000 0.01240000
|
| 1029 |
+
vn -0.90320000 0.40120000 0.15250000
|
| 1030 |
+
vn -0.96200000 0.27260000 0.01220000
|
| 1031 |
+
vn -0.93670000 0.34600000 -0.05310000
|
| 1032 |
+
vn -0.90320000 0.40120000 0.15250000
|
| 1033 |
+
vn -0.88090000 0.46370000 0.09540000
|
| 1034 |
+
vn -0.84800000 0.52970000 0.01890000
|
| 1035 |
+
vn -0.84800000 0.52970000 0.01890000
|
| 1036 |
+
vn -0.80500000 0.58420000 0.10350000
|
| 1037 |
+
vn -0.77250000 0.63400000 0.03630000
|
| 1038 |
+
vn -0.77250000 0.63400000 0.03630000
|
| 1039 |
+
vn -0.71480000 0.69430000 0.08340000
|
| 1040 |
+
vn -0.68910000 0.72460000 0.01320000
|
| 1041 |
+
vn -0.56170000 0.82720000 0.01310000
|
| 1042 |
+
vn -0.60750000 0.78810000 0.09940000
|
| 1043 |
+
vn -0.68910000 0.72460000 0.01320000
|
| 1044 |
+
vn -0.56170000 0.82720000 0.01310000
|
| 1045 |
+
vn -0.43430000 0.88840000 0.14850000
|
| 1046 |
+
vn -0.30910000 0.95090000 0.01880000
|
| 1047 |
+
vn -0.37800000 0.92080000 0.09620000
|
| 1048 |
+
vn -0.43430000 0.88840000 0.14850000
|
| 1049 |
+
vn -0.49550000 0.86680000 -0.05620000
|
| 1050 |
+
vn -0.30910000 0.95090000 0.01880000
|
| 1051 |
+
vn -0.18430000 0.98210000 0.03820000
|
| 1052 |
+
vn -0.24200000 0.96480000 0.10300000
|
| 1053 |
+
vn -0.06210000 0.99800000 0.01260000
|
| 1054 |
+
vn -0.10340000 0.99080000 0.08680000
|
| 1055 |
+
vn -0.18430000 0.98210000 0.03820000
|
| 1056 |
+
vn -0.99930000 -0.01090000 0.03630000
|
| 1057 |
+
vn -0.73110000 0.04710000 0.68070000
|
| 1058 |
+
vn -0.72720000 -0.04850000 0.68470000
|
| 1059 |
+
vn -0.99220000 -0.07050000 0.10260000
|
| 1060 |
+
vn -0.99390000 0.07080000 0.08440000
|
| 1061 |
+
vn -0.90320000 0.40120000 0.15250000
|
| 1062 |
+
vn -0.67990000 0.25720000 0.68670000
|
| 1063 |
+
vn -0.93670000 0.34600000 -0.05310000
|
| 1064 |
+
vn -0.70770000 0.15670000 0.68900000
|
| 1065 |
+
vn -0.97240000 0.21130000 0.09930000
|
| 1066 |
+
vn -0.96200000 0.27260000 0.01220000
|
| 1067 |
+
vn -0.93670000 0.34600000 -0.05310000
|
| 1068 |
+
vn -0.67990000 0.25720000 0.68670000
|
| 1069 |
+
vn -0.64020000 0.32950000 0.69390000
|
| 1070 |
+
vn -0.88090000 0.46370000 0.09540000
|
| 1071 |
+
vn -0.64080000 0.30380000 0.70500000
|
| 1072 |
+
vn -0.84800000 0.52970000 0.01890000
|
| 1073 |
+
vn -0.88090000 0.46370000 0.09540000
|
| 1074 |
+
vn -0.59370000 0.43580000 0.67640000
|
| 1075 |
+
vn -0.64020000 0.32950000 0.69390000
|
| 1076 |
+
vn -0.80500000 0.58420000 0.10350000
|
| 1077 |
+
vn -0.40390000 0.58780000 0.70100000
|
| 1078 |
+
vn -0.44110000 0.57620000 0.68800000
|
| 1079 |
+
vn -0.60750000 0.78810000 0.09940000
|
| 1080 |
+
vn -0.43430000 0.88840000 0.14850000
|
| 1081 |
+
vn -0.56170000 0.82720000 0.01310000
|
| 1082 |
+
vn -0.35680000 0.63680000 0.68350000
|
| 1083 |
+
vn -0.49550000 0.86680000 -0.05620000
|
| 1084 |
+
vn -0.37800000 0.92080000 0.09620000
|
| 1085 |
+
vn -0.49550000 0.86680000 -0.05620000
|
| 1086 |
+
vn -0.28090000 0.66850000 0.68860000
|
| 1087 |
+
vn -0.35680000 0.63680000 0.68350000
|
| 1088 |
+
vn -0.17630000 0.70540000 0.68650000
|
| 1089 |
+
vn -0.37800000 0.92080000 0.09620000
|
| 1090 |
+
vn -0.30910000 0.95090000 0.01880000
|
| 1091 |
+
vn -0.24200000 0.96480000 0.10300000
|
| 1092 |
+
vn -0.28090000 0.66850000 0.68860000
|
| 1093 |
+
vn -0.23040000 0.66740000 0.70810000
|
| 1094 |
+
vn 0.09120000 0.70800000 0.70030000
|
| 1095 |
+
vn 0.13440000 0.71700000 0.68400000
|
| 1096 |
+
vn 0.03350000 0.72510000 0.68780000
|
| 1097 |
+
vn 0.10140000 0.99480000 0.01130000
|
| 1098 |
+
vn 0.04080000 0.99430000 0.09860000
|
| 1099 |
+
vn 0.17950000 0.98240000 -0.05210000
|
| 1100 |
+
vn 0.23840000 0.95970000 0.14860000
|
| 1101 |
+
vn 0.21960000 0.70130000 0.67820000
|
| 1102 |
+
vn 0.30380000 0.94790000 0.09600000
|
| 1103 |
+
vn 0.17950000 0.98240000 -0.05210000
|
| 1104 |
+
vn 0.13440000 0.71700000 0.68400000
|
| 1105 |
+
vn 0.43640000 0.89390000 0.10230000
|
| 1106 |
+
vn 0.30380000 0.94790000 0.09600000
|
| 1107 |
+
vn 0.37440000 0.92710000 0.01760000
|
| 1108 |
+
vn 0.21960000 0.70130000 0.67820000
|
| 1109 |
+
vn 0.27030000 0.66610000 0.69520000
|
| 1110 |
+
vn 0.32320000 0.65640000 0.68170000
|
| 1111 |
+
vn 0.71710000 0.69680000 0.01270000
|
| 1112 |
+
vn 0.67010000 0.73560000 0.09940000
|
| 1113 |
+
vn 0.76520000 0.64050000 -0.06550000
|
| 1114 |
+
vn 0.49380000 0.53800000 0.68310000
|
| 1115 |
+
vn 0.79940000 0.58180000 0.14990000
|
| 1116 |
+
vn 0.55360000 0.45030000 0.70050000
|
| 1117 |
+
vn 0.55360000 0.45030000 0.70050000
|
| 1118 |
+
vn 0.61700000 0.39740000 0.67920000
|
| 1119 |
+
vn 0.76520000 0.64050000 -0.06550000
|
| 1120 |
+
vn 0.84570000 0.52500000 0.09630000
|
| 1121 |
+
vn 0.55160000 0.45880000 0.69660000
|
| 1122 |
+
vn 0.61700000 0.39740000 0.67920000
|
| 1123 |
+
vn 0.66160000 0.29310000 0.69020000
|
| 1124 |
+
vn 0.84570000 0.52500000 0.09630000
|
| 1125 |
+
vn 0.88260000 0.46940000 0.02580000
|
| 1126 |
+
vn 0.90720000 0.40750000 0.10410000
|
| 1127 |
+
vn 0.72460000 -0.09760000 0.68220000
|
| 1128 |
+
vn 0.72530000 0.00780000 0.68840000
|
| 1129 |
+
vn 0.99890000 -0.00860000 -0.04710000
|
| 1130 |
+
vn 0.98640000 -0.13140000 0.09910000
|
| 1131 |
+
vn 0.95620000 -0.27410000 0.10240000
|
| 1132 |
+
vn 0.97800000 -0.20780000 0.01800000
|
| 1133 |
+
vn 0.69500000 -0.20210000 0.69000000
|
| 1134 |
+
vn 0.98640000 -0.13140000 0.09910000
|
| 1135 |
+
vn 0.72460000 -0.09760000 0.68220000
|
| 1136 |
+
vn 0.68980000 -0.16860000 0.70410000
|
| 1137 |
+
vn 0.60170000 -0.38400000 0.70040000
|
| 1138 |
+
vn 0.84110000 -0.53170000 0.09930000
|
| 1139 |
+
vn 0.71170000 -0.68610000 0.15110000
|
| 1140 |
+
vn 0.76250000 -0.64440000 -0.05800000
|
| 1141 |
+
vn 0.54090000 -0.48310000 0.68850000
|
| 1142 |
+
vn 0.64470000 -0.35750000 0.67570000
|
| 1143 |
+
vn 0.81080000 -0.58520000 0.01230000
|
| 1144 |
+
vn 0.54470000 -0.46800000 0.69590000
|
| 1145 |
+
vn 0.76250000 -0.64440000 -0.05800000
|
| 1146 |
+
vn 0.54470000 -0.46800000 0.69590000
|
| 1147 |
+
vn 0.49770000 -0.53650000 0.68150000
|
| 1148 |
+
vn 0.67070000 -0.73550000 0.09600000
|
| 1149 |
+
vn 0.67070000 -0.73550000 0.09600000
|
| 1150 |
+
vn 0.61560000 -0.78780000 0.01910000
|
| 1151 |
+
vn 0.55850000 -0.82310000 0.10260000
|
| 1152 |
+
vn 0.49770000 -0.53650000 0.68150000
|
| 1153 |
+
vn 0.40030000 -0.59160000 0.69980000
|
| 1154 |
+
vn 0.16440000 -0.98410000 -0.06650000
|
| 1155 |
+
vn 0.02940000 -0.72270000 0.69050000
|
| 1156 |
+
vn 0.04790000 -0.71370000 0.69880000
|
| 1157 |
+
vn 0.13540000 -0.71910000 0.68160000
|
| 1158 |
+
vn 0.04230000 -0.99390000 0.10220000
|
| 1159 |
+
vn -0.04790000 -0.99860000 0.02460000
|
| 1160 |
+
vn -0.10340000 -0.98970000 0.09950000
|
| 1161 |
+
vn 0.04230000 -0.99390000 0.10220000
|
| 1162 |
+
vn 0.02940000 -0.72270000 0.69050000
|
| 1163 |
+
vn -0.07890000 -0.72630000 0.68290000
|
| 1164 |
+
vn -0.43140000 -0.55980000 0.70750000
|
| 1165 |
+
vn -0.60430000 -0.79050000 0.09980000
|
| 1166 |
+
vn -0.50570000 -0.86130000 -0.04920000
|
| 1167 |
+
vn -0.35530000 -0.63910000 0.68220000
|
| 1168 |
+
vn -0.43140000 -0.55980000 0.70750000
|
| 1169 |
+
vn -0.42670000 -0.57150000 0.70100000
|
| 1170 |
+
vn -0.60430000 -0.79050000 0.09980000
|
| 1171 |
+
vn -0.66890000 -0.74310000 0.01920000
|
| 1172 |
+
vn -0.71320000 -0.69340000 0.10240000
|
| 1173 |
+
vn -0.52580000 -0.50970000 0.68100000
|
| 1174 |
+
vn -0.67990000 -0.25740000 0.68670000
|
| 1175 |
+
vn -0.70860000 -0.15500000 0.68840000
|
| 1176 |
+
vn -0.94150000 -0.33380000 -0.04700000
|
| 1177 |
+
vn -0.97160000 -0.21490000 0.09940000
|
| 1178 |
+
vn -0.97160000 -0.21490000 0.09940000
|
| 1179 |
+
vn -0.70860000 -0.15500000 0.68840000
|
| 1180 |
+
vn -0.99010000 -0.13930000 0.01850000
|
| 1181 |
+
vn -0.70010000 -0.10460000 0.70640000
|
| 1182 |
+
vn -0.99220000 -0.07050000 0.10260000
|
| 1183 |
+
vn -0.72720000 -0.04850000 0.68470000
|
| 1184 |
+
vn -0.64910000 -0.32950000 0.68560000
|
| 1185 |
+
vn -0.57420000 -0.44730000 0.68570000
|
| 1186 |
+
vn -0.57740000 -0.42180000 0.69900000
|
| 1187 |
+
vn -0.80590000 -0.58530000 0.08880000
|
| 1188 |
+
vn -0.83320000 -0.55280000 0.01350000
|
| 1189 |
+
vn -0.87990000 -0.46540000 0.09520000
|
| 1190 |
+
vn -0.67990000 -0.25740000 0.68670000
|
| 1191 |
+
vn -0.94150000 -0.33380000 -0.04700000
|
| 1192 |
+
vn -0.64910000 -0.32950000 0.68560000
|
| 1193 |
+
vn -0.94920000 -0.27310000 0.15660000
|
| 1194 |
+
vn -0.65650000 -0.28630000 0.69790000
|
| 1195 |
+
vn -0.91230000 -0.40960000 0.00460000
|
| 1196 |
+
vn -0.87990000 -0.46540000 0.09520000
|
| 1197 |
+
vn -0.80590000 -0.58530000 0.08880000
|
| 1198 |
+
vn -0.52580000 -0.50970000 0.68100000
|
| 1199 |
+
vn -0.71320000 -0.69340000 0.10240000
|
| 1200 |
+
vn -0.57740000 -0.42180000 0.69900000
|
| 1201 |
+
vn -0.75840000 -0.65070000 0.03750000
|
| 1202 |
+
vn -0.24260000 -0.96650000 0.08410000
|
| 1203 |
+
vn -0.11560000 -0.73640000 0.66660000
|
| 1204 |
+
vn -0.37330000 -0.92280000 0.09570000
|
| 1205 |
+
vn -0.16650000 -0.68490000 0.70930000
|
| 1206 |
+
vn -0.28290000 -0.95910000 0.01260000
|
| 1207 |
+
vn -0.27110000 -0.66730000 0.69370000
|
| 1208 |
+
vn -0.28360000 -0.66760000 0.68840000
|
| 1209 |
+
vn -0.43560000 -0.90010000 0.00410000
|
| 1210 |
+
vn -0.55140000 -0.81890000 0.15910000
|
| 1211 |
+
vn -0.28360000 -0.66760000 0.68840000
|
| 1212 |
+
vn -0.50570000 -0.86130000 -0.04920000
|
| 1213 |
+
vn -0.37330000 -0.92280000 0.09570000
|
| 1214 |
+
vn -0.35530000 -0.63910000 0.68220000
|
| 1215 |
+
vn -0.16650000 -0.68490000 0.70930000
|
| 1216 |
+
vn -0.07890000 -0.72630000 0.68290000
|
| 1217 |
+
vn -0.16530000 -0.98550000 0.03780000
|
| 1218 |
+
vn -0.24260000 -0.96650000 0.08410000
|
| 1219 |
+
vn -0.10340000 -0.98970000 0.09950000
|
| 1220 |
+
vn 0.43720000 -0.89510000 0.08760000
|
| 1221 |
+
vn 0.39970000 -0.91660000 0.01140000
|
| 1222 |
+
vn 0.30560000 -0.94730000 0.09580000
|
| 1223 |
+
vn 0.21020000 -0.68670000 0.69590000
|
| 1224 |
+
vn 0.32180000 -0.65770000 0.68110000
|
| 1225 |
+
vn 0.24490000 -0.96950000 0.00470000
|
| 1226 |
+
vn 0.30560000 -0.94730000 0.09580000
|
| 1227 |
+
vn 0.16440000 -0.98410000 -0.06650000
|
| 1228 |
+
vn 0.21020000 -0.68670000 0.69590000
|
| 1229 |
+
vn 0.22550000 -0.68880000 0.68900000
|
| 1230 |
+
vn 0.13540000 -0.71910000 0.68160000
|
| 1231 |
+
vn 0.10040000 -0.98210000 0.15960000
|
| 1232 |
+
vn 0.32180000 -0.65770000 0.68110000
|
| 1233 |
+
vn 0.43720000 -0.89510000 0.08760000
|
| 1234 |
+
vn 0.50910000 -0.85990000 0.03770000
|
| 1235 |
+
vn 0.55850000 -0.82310000 0.10260000
|
| 1236 |
+
vn 0.39210000 -0.59250000 0.70380000
|
| 1237 |
+
vn 0.40030000 -0.59160000 0.69980000
|
| 1238 |
+
vn 0.84110000 -0.53170000 0.09930000
|
| 1239 |
+
vn 0.60170000 -0.38400000 0.70040000
|
| 1240 |
+
vn 0.67260000 -0.29560000 0.67840000
|
| 1241 |
+
vn 0.89540000 -0.44520000 0.01280000
|
| 1242 |
+
vn 0.90950000 -0.40710000 0.08380000
|
| 1243 |
+
vn 0.69500000 -0.20210000 0.69000000
|
| 1244 |
+
vn 0.90950000 -0.40710000 0.08380000
|
| 1245 |
+
vn 0.67260000 -0.29560000 0.67840000
|
| 1246 |
+
vn 0.94270000 -0.33150000 0.03640000
|
| 1247 |
+
vn 0.95620000 -0.27410000 0.10240000
|
| 1248 |
+
vn 0.70240000 0.20210000 0.68250000
|
| 1249 |
+
vn 0.71560000 0.08760000 0.69300000
|
| 1250 |
+
vn 0.95760000 0.27460000 0.08720000
|
| 1251 |
+
vn 0.97200000 0.23450000 0.01200000
|
| 1252 |
+
vn 0.98610000 0.13610000 0.09590000
|
| 1253 |
+
vn 0.71560000 0.08760000 0.69300000
|
| 1254 |
+
vn 0.70560000 0.05560000 0.70640000
|
| 1255 |
+
vn 0.72530000 0.00780000 0.68840000
|
| 1256 |
+
vn 0.98560000 -0.06810000 0.15490000
|
| 1257 |
+
vn 0.99730000 0.07290000 0.00480000
|
| 1258 |
+
vn 0.98610000 0.13610000 0.09590000
|
| 1259 |
+
vn 0.99890000 -0.00860000 -0.04710000
|
| 1260 |
+
vn 0.66160000 0.29310000 0.69020000
|
| 1261 |
+
vn 0.95760000 0.27460000 0.08720000
|
| 1262 |
+
vn 0.93520000 0.35200000 0.03790000
|
| 1263 |
+
vn 0.90720000 0.40750000 0.10410000
|
| 1264 |
+
vn 0.70240000 0.20210000 0.68250000
|
| 1265 |
+
vn 0.66200000 0.26120000 0.70250000
|
| 1266 |
+
vn 0.40250000 0.60280000 0.68900000
|
| 1267 |
+
vn 0.49380000 0.53800000 0.68310000
|
| 1268 |
+
vn 0.41760000 0.57990000 0.69950000
|
| 1269 |
+
vn 0.55930000 0.82480000 0.08360000
|
| 1270 |
+
vn 0.67010000 0.73560000 0.09940000
|
| 1271 |
+
vn 0.59390000 0.80440000 0.01300000
|
| 1272 |
+
vn 0.43640000 0.89390000 0.10230000
|
| 1273 |
+
vn 0.49020000 0.87090000 0.03630000
|
| 1274 |
+
vn 0.55930000 0.82480000 0.08360000
|
| 1275 |
+
vn 0.32320000 0.65640000 0.68170000
|
| 1276 |
+
vn 0.40250000 0.60280000 0.68900000
|
| 1277 |
+
vn -0.10340000 0.99080000 0.08680000
|
| 1278 |
+
vn -0.04790000 0.71150000 0.70100000
|
| 1279 |
+
vn 0.04080000 0.99430000 0.09860000
|
| 1280 |
+
vn -0.07620000 0.72040000 0.68930000
|
| 1281 |
+
vn 0.03350000 0.72510000 0.68780000
|
| 1282 |
+
vn -0.06210000 0.99800000 0.01260000
|
| 1283 |
+
vn -0.18430000 0.98210000 0.03820000
|
| 1284 |
+
vn -0.24200000 0.96480000 0.10300000
|
| 1285 |
+
vn -0.10340000 0.99080000 0.08680000
|
| 1286 |
+
vn -0.17630000 0.70540000 0.68650000
|
| 1287 |
+
vn -0.07620000 0.72040000 0.68930000
|
| 1288 |
+
vn -0.51900000 0.49680000 0.69560000
|
| 1289 |
+
vn -0.71480000 0.69430000 0.08340000
|
| 1290 |
+
vn -0.60750000 0.78810000 0.09940000
|
| 1291 |
+
vn -0.68910000 0.72460000 0.01320000
|
| 1292 |
+
vn -0.54250000 0.48940000 0.68280000
|
| 1293 |
+
vn -0.44110000 0.57620000 0.68800000
|
| 1294 |
+
vn -0.77250000 0.63400000 0.03630000
|
| 1295 |
+
vn -0.51900000 0.49680000 0.69560000
|
| 1296 |
+
vn -0.59370000 0.43580000 0.67640000
|
| 1297 |
+
vn -0.80500000 0.58420000 0.10350000
|
| 1298 |
+
vn -0.71480000 0.69430000 0.08340000
|
| 1299 |
+
vn -0.73110000 0.04710000 0.68070000
|
| 1300 |
+
vn -0.70130000 0.12030000 0.70260000
|
| 1301 |
+
vn -0.70770000 0.15670000 0.68900000
|
| 1302 |
+
vn -0.99360000 0.11210000 0.01240000
|
| 1303 |
+
vn -0.97240000 0.21130000 0.09930000
|
| 1304 |
+
vn -0.99390000 0.07080000 0.08440000
|
| 1305 |
+
vn 0.32180000 -0.65770000 0.68110000
|
| 1306 |
+
vn 0.22900000 -0.91350000 0.33630000
|
| 1307 |
+
vn 0.21020000 -0.68670000 0.69590000
|
| 1308 |
+
vn 0.22550000 -0.68880000 0.68900000
|
| 1309 |
+
vn 0.39210000 -0.59250000 0.70380000
|
| 1310 |
+
vn 0.49460000 -0.75200000 0.43580000
|
| 1311 |
+
vn 0.33210000 -0.78740000 0.51930000
|
| 1312 |
+
vn 0.11240000 -0.91180000 0.39500000
|
| 1313 |
+
vn 0.04790000 -0.71370000 0.69880000
|
| 1314 |
+
vn 0.22550000 -0.68880000 0.68900000
|
| 1315 |
+
vn 0.12700000 -0.89450000 0.42860000
|
| 1316 |
+
vn 0.22900000 -0.91350000 0.33630000
|
| 1317 |
+
vn 0.13540000 -0.71910000 0.68160000
|
| 1318 |
+
vn -0.07890000 -0.72630000 0.68290000
|
| 1319 |
+
vn 0.04790000 -0.71370000 0.69880000
|
| 1320 |
+
vn -0.16650000 -0.68490000 0.70930000
|
| 1321 |
+
vn -0.11560000 -0.73640000 0.66660000
|
| 1322 |
+
vn 0.02940000 -0.72270000 0.69050000
|
| 1323 |
+
vn -0.04900000 -0.85460000 0.51700000
|
| 1324 |
+
vn -0.21550000 -0.91260000 0.34750000
|
| 1325 |
+
vn 0.11240000 -0.91180000 0.39500000
|
| 1326 |
+
vn -0.21550000 -0.91260000 0.34750000
|
| 1327 |
+
vn -0.11560000 -0.73640000 0.66660000
|
| 1328 |
+
vn -0.28990000 -0.86180000 0.41630000
|
| 1329 |
+
vn -0.28230000 -0.85800000 0.42920000
|
| 1330 |
+
vn -0.27110000 -0.66730000 0.69370000
|
| 1331 |
+
vn -0.28360000 -0.66760000 0.68840000
|
| 1332 |
+
vn -0.35530000 -0.63910000 0.68220000
|
| 1333 |
+
vn -0.43140000 -0.55980000 0.70750000
|
| 1334 |
+
vn -0.55630000 -0.72100000 0.41320000
|
| 1335 |
+
vn -0.54030000 -0.71910000 0.43700000
|
| 1336 |
+
vn -0.28230000 -0.85800000 0.42920000
|
| 1337 |
+
vn -0.40950000 -0.75150000 0.51730000
|
| 1338 |
+
vn -0.27110000 -0.66730000 0.69370000
|
| 1339 |
+
vn -0.42670000 -0.57150000 0.70100000
|
| 1340 |
+
vn -0.57420000 -0.44730000 0.68570000
|
| 1341 |
+
vn -0.57740000 -0.42180000 0.69900000
|
| 1342 |
+
vn -0.42670000 -0.57150000 0.70100000
|
| 1343 |
+
vn -0.62880000 -0.57860000 0.51940000
|
| 1344 |
+
vn -0.78180000 -0.52480000 0.33660000
|
| 1345 |
+
vn -0.52580000 -0.50970000 0.68100000
|
| 1346 |
+
vn -0.54030000 -0.71910000 0.43700000
|
| 1347 |
+
vn 0.49770000 -0.53650000 0.68150000
|
| 1348 |
+
vn 0.56740000 -0.64060000 0.51750000
|
| 1349 |
+
vn 0.49210000 -0.76310000 0.41900000
|
| 1350 |
+
vn 0.40030000 -0.59160000 0.69980000
|
| 1351 |
+
vn 0.54470000 -0.46800000 0.69590000
|
| 1352 |
+
vn 0.39210000 -0.59250000 0.70380000
|
| 1353 |
+
vn 0.49460000 -0.75200000 0.43580000
|
| 1354 |
+
vn 0.54090000 -0.48310000 0.68850000
|
| 1355 |
+
vn 0.71450000 -0.55620000 0.42440000
|
| 1356 |
+
vn 0.54090000 -0.48310000 0.68850000
|
| 1357 |
+
vn 0.71450000 -0.55620000 0.42440000
|
| 1358 |
+
vn 0.71530000 -0.61860000 0.32520000
|
| 1359 |
+
vn 0.84280000 -0.48570000 0.23180000
|
| 1360 |
+
vn 0.64470000 -0.35750000 0.67570000
|
| 1361 |
+
vn 0.67260000 -0.29560000 0.67840000
|
| 1362 |
+
vn 0.90400000 -0.26610000 0.33470000
|
| 1363 |
+
vn 0.68980000 -0.16860000 0.70410000
|
| 1364 |
+
vn 0.60170000 -0.38400000 0.70040000
|
| 1365 |
+
vn 0.85590000 -0.31560000 0.40960000
|
| 1366 |
+
vn 0.84280000 -0.48570000 0.23180000
|
| 1367 |
+
vn 0.64470000 -0.35750000 0.67570000
|
| 1368 |
+
vn 0.69500000 -0.20210000 0.69000000
|
| 1369 |
+
vn 0.68980000 -0.16860000 0.70410000
|
| 1370 |
+
vn 0.70560000 0.05560000 0.70640000
|
| 1371 |
+
vn 0.92810000 0.06680000 0.36620000
|
| 1372 |
+
vn 0.87650000 -0.20730000 0.43460000
|
| 1373 |
+
vn 0.85010000 -0.03950000 0.52510000
|
| 1374 |
+
vn 0.90400000 -0.26610000 0.33470000
|
| 1375 |
+
vn 0.72460000 -0.09760000 0.68220000
|
| 1376 |
+
vn 0.72530000 0.00780000 0.68840000
|
| 1377 |
+
vn 0.83190000 0.17240000 0.52750000
|
| 1378 |
+
vn 0.71560000 0.08760000 0.69300000
|
| 1379 |
+
vn 0.70560000 0.05560000 0.70640000
|
| 1380 |
+
vn 0.82720000 0.37280000 0.42050000
|
| 1381 |
+
vn 0.70240000 0.20210000 0.68250000
|
| 1382 |
+
vn 0.66200000 0.26120000 0.70250000
|
| 1383 |
+
vn 0.92810000 0.06680000 0.36620000
|
| 1384 |
+
vn 0.10830000 0.87500000 0.47180000
|
| 1385 |
+
vn 0.03350000 0.72510000 0.68780000
|
| 1386 |
+
vn -0.05870000 0.87340000 0.48340000
|
| 1387 |
+
vn 0.09120000 0.70800000 0.70030000
|
| 1388 |
+
vn 0.12860000 0.88540000 0.44670000
|
| 1389 |
+
vn -0.04790000 0.71150000 0.70100000
|
| 1390 |
+
vn 0.13440000 0.71700000 0.68400000
|
| 1391 |
+
vn 0.09120000 0.70800000 0.70030000
|
| 1392 |
+
vn 0.21960000 0.70130000 0.67820000
|
| 1393 |
+
vn 0.27030000 0.66610000 0.69520000
|
| 1394 |
+
vn 0.12860000 0.88540000 0.44670000
|
| 1395 |
+
vn 0.24100000 0.81850000 0.52150000
|
| 1396 |
+
vn 0.40760000 0.84840000 0.33770000
|
| 1397 |
+
vn 0.27030000 0.66610000 0.69520000
|
| 1398 |
+
vn 0.40760000 0.84840000 0.33770000
|
| 1399 |
+
vn 0.32320000 0.65640000 0.68170000
|
| 1400 |
+
vn 0.47750000 0.77410000 0.41560000
|
| 1401 |
+
vn 0.48930000 0.77600000 0.39800000
|
| 1402 |
+
vn 0.40250000 0.60280000 0.68900000
|
| 1403 |
+
vn 0.41760000 0.57990000 0.69950000
|
| 1404 |
+
vn 0.49380000 0.53800000 0.68310000
|
| 1405 |
+
vn 0.72400000 0.54550000 0.42220000
|
| 1406 |
+
vn 0.55160000 0.45880000 0.69660000
|
| 1407 |
+
vn 0.57390000 0.63660000 0.51510000
|
| 1408 |
+
vn 0.48930000 0.77600000 0.39800000
|
| 1409 |
+
vn 0.41760000 0.57990000 0.69950000
|
| 1410 |
+
vn 0.55360000 0.45030000 0.70050000
|
| 1411 |
+
vn 0.66160000 0.29310000 0.69020000
|
| 1412 |
+
vn 0.66200000 0.26120000 0.70250000
|
| 1413 |
+
vn 0.72400000 0.54550000 0.42220000
|
| 1414 |
+
vn 0.61700000 0.39740000 0.67920000
|
| 1415 |
+
vn 0.55160000 0.45880000 0.69660000
|
| 1416 |
+
vn 0.82720000 0.37280000 0.42050000
|
| 1417 |
+
vn 0.73530000 0.61600000 0.28280000
|
| 1418 |
+
vn 0.88990000 0.35180000 0.29040000
|
| 1419 |
+
vn -0.64020000 0.32950000 0.69390000
|
| 1420 |
+
vn -0.51900000 0.49680000 0.69560000
|
| 1421 |
+
vn -0.54250000 0.48940000 0.68280000
|
| 1422 |
+
vn -0.81090000 0.40300000 0.42440000
|
| 1423 |
+
vn -0.66370000 0.66840000 0.33580000
|
| 1424 |
+
vn -0.64080000 0.30380000 0.70500000
|
| 1425 |
+
vn -0.59370000 0.43580000 0.67640000
|
| 1426 |
+
vn -0.68990000 0.50410000 0.51950000
|
| 1427 |
+
vn -0.66370000 0.66840000 0.33580000
|
| 1428 |
+
vn -0.56580000 0.72170000 0.39890000
|
| 1429 |
+
vn -0.44110000 0.57620000 0.68800000
|
| 1430 |
+
vn -0.40390000 0.58780000 0.70100000
|
| 1431 |
+
vn -0.54250000 0.48940000 0.68280000
|
| 1432 |
+
vn -0.56750000 0.71190000 0.41370000
|
| 1433 |
+
vn -0.23040000 0.66740000 0.70810000
|
| 1434 |
+
vn -0.56580000 0.72170000 0.39890000
|
| 1435 |
+
vn -0.35680000 0.63680000 0.68350000
|
| 1436 |
+
vn -0.40390000 0.58780000 0.70100000
|
| 1437 |
+
vn -0.28090000 0.66850000 0.68860000
|
| 1438 |
+
vn -0.41040000 0.75450000 0.51210000
|
| 1439 |
+
vn -0.30010000 0.84370000 0.44510000
|
| 1440 |
+
vn -0.29610000 0.85110000 0.43350000
|
| 1441 |
+
vn -0.23040000 0.66740000 0.70810000
|
| 1442 |
+
vn -0.07620000 0.72040000 0.68930000
|
| 1443 |
+
vn -0.17630000 0.70540000 0.68650000
|
| 1444 |
+
vn -0.04790000 0.71150000 0.70100000
|
| 1445 |
+
vn -0.02910000 0.90440000 0.42570000
|
| 1446 |
+
vn -0.16220000 0.84220000 0.51420000
|
| 1447 |
+
vn -0.29610000 0.85110000 0.43350000
|
| 1448 |
+
vn -0.05870000 0.87340000 0.48340000
|
| 1449 |
+
vn -0.65650000 -0.28630000 0.69790000
|
| 1450 |
+
vn -0.64910000 -0.32950000 0.68560000
|
| 1451 |
+
vn -0.57420000 -0.44730000 0.68570000
|
| 1452 |
+
vn -0.81610000 -0.41770000 0.39950000
|
| 1453 |
+
vn -0.78180000 -0.52480000 0.33660000
|
| 1454 |
+
vn -0.79920000 -0.42410000 0.42600000
|
| 1455 |
+
vn -0.93490000 -0.08820000 0.34390000
|
| 1456 |
+
vn -0.89230000 -0.12140000 0.43480000
|
| 1457 |
+
vn -0.81870000 -0.25350000 0.51530000
|
| 1458 |
+
vn -0.81610000 -0.41770000 0.39950000
|
| 1459 |
+
vn -0.67990000 -0.25740000 0.68670000
|
| 1460 |
+
vn -0.65650000 -0.28630000 0.69790000
|
| 1461 |
+
vn -0.70010000 -0.10460000 0.70640000
|
| 1462 |
+
vn -0.70860000 -0.15500000 0.68840000
|
| 1463 |
+
vn -0.72720000 -0.04850000 0.68470000
|
| 1464 |
+
vn -0.70010000 -0.10460000 0.70640000
|
| 1465 |
+
vn -0.70130000 0.12030000 0.70260000
|
| 1466 |
+
vn -0.90390000 0.11430000 0.41210000
|
| 1467 |
+
vn -0.73110000 0.04710000 0.68070000
|
| 1468 |
+
vn -0.93490000 -0.08820000 0.34390000
|
| 1469 |
+
vn -0.89500000 0.10460000 0.43370000
|
| 1470 |
+
vn -0.70770000 0.15670000 0.68900000
|
| 1471 |
+
vn -0.81450000 0.25780000 0.51970000
|
| 1472 |
+
vn -0.81310000 0.41010000 0.41310000
|
| 1473 |
+
vn -0.89500000 0.10460000 0.43370000
|
| 1474 |
+
vn -0.81090000 0.40300000 0.42440000
|
| 1475 |
+
vn -0.67990000 0.25720000 0.68670000
|
| 1476 |
+
vn -0.70130000 0.12030000 0.70260000
|
| 1477 |
+
vn -0.64080000 0.30380000 0.70500000
|
| 1478 |
+
vn 0.00010000 -0.00000000 1.00000000
|
| 1479 |
+
vn 0.00030000 -0.00000000 1.00000000
|
| 1480 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1481 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1482 |
+
vn 0.00030000 -0.00000000 1.00000000
|
| 1483 |
+
vn 0.00010000 -0.00000000 1.00000000
|
| 1484 |
+
vn 0.00010000 -0.00010000 1.00000000
|
| 1485 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1486 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1487 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1488 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1489 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1490 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1491 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1492 |
+
vn 0.00010000 -0.00020000 1.00000000
|
| 1493 |
+
vn -0.00000000 -0.00010000 1.00000000
|
| 1494 |
+
vn 0.00010000 -0.00020000 1.00000000
|
| 1495 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1496 |
+
vn 0.00000000 -0.00020000 1.00000000
|
| 1497 |
+
vn -0.00000000 -0.00010000 1.00000000
|
| 1498 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1499 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1500 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1501 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1502 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1503 |
+
vn -0.00030000 -0.00010000 1.00000000
|
| 1504 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1505 |
+
vn -0.00030000 -0.00010000 1.00000000
|
| 1506 |
+
vn -0.00020000 -0.00000000 1.00000000
|
| 1507 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1508 |
+
vn 0.00010000 -0.00000000 1.00000000
|
| 1509 |
+
vn 0.00010000 -0.00000000 1.00000000
|
| 1510 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1511 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1512 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1513 |
+
vn 0.00010000 -0.00000000 1.00000000
|
| 1514 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1515 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1516 |
+
vn -0.00010000 0.00010000 1.00000000
|
| 1517 |
+
vn -0.00040000 0.00020000 1.00000000
|
| 1518 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1519 |
+
vn -0.00040000 0.00020000 1.00000000
|
| 1520 |
+
vn -0.00020000 0.00010000 1.00000000
|
| 1521 |
+
vn -0.00030000 0.00020000 1.00000000
|
| 1522 |
+
vn -0.00020000 0.00010000 1.00000000
|
| 1523 |
+
vn -0.00010000 0.00020000 1.00000000
|
| 1524 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1525 |
+
vn -0.00010000 0.00010000 1.00000000
|
| 1526 |
+
vn -0.00010000 0.00010000 1.00000000
|
| 1527 |
+
vn -0.00010000 0.00020000 1.00000000
|
| 1528 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1529 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1530 |
+
vn 0.00000000 -0.00050000 1.00000000
|
| 1531 |
+
vn -0.00000000 -0.00010000 1.00000000
|
| 1532 |
+
vn 0.00000000 -0.00020000 1.00000000
|
| 1533 |
+
vn 0.00000000 -0.00050000 1.00000000
|
| 1534 |
+
vn -0.00010000 -0.00040000 1.00000000
|
| 1535 |
+
vn 0.00000000 -0.00020000 1.00000000
|
| 1536 |
+
vn 0.00000000 -0.00020000 1.00000000
|
| 1537 |
+
vn 0.34810000 0.93740000 0.00420000
|
| 1538 |
+
vn 0.37790000 0.92580000 0.00450000
|
| 1539 |
+
vn -0.00010000 -0.00040000 1.00000000
|
| 1540 |
+
vn 0.00010000 0.00010000 1.00000000
|
| 1541 |
+
vn 0.00000000 -0.00020000 1.00000000
|
| 1542 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1543 |
+
vn 0.00010000 0.00010000 1.00000000
|
| 1544 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1545 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1546 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1547 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1548 |
+
vn 0.90370000 0.42810000 0.00170000
|
| 1549 |
+
vn 0.73530000 0.61600000 0.28280000
|
| 1550 |
+
vn 0.91110000 0.41230000 0.00100000
|
| 1551 |
+
vn 0.88990000 0.35180000 0.29040000
|
| 1552 |
+
vn 0.79760000 0.60320000 -0.00050000
|
| 1553 |
+
vn -0.18050000 0.98360000 0.00040000
|
| 1554 |
+
vn -0.08000000 0.99680000 0.00270000
|
| 1555 |
+
vn -0.03200000 0.99950000 0.00110000
|
| 1556 |
+
vn -0.16220000 0.84220000 0.51420000
|
| 1557 |
+
vn -0.02910000 0.90440000 0.42570000
|
| 1558 |
+
vn -0.95060000 0.31050000 0.00020000
|
| 1559 |
+
vn -0.81450000 0.25780000 0.51970000
|
| 1560 |
+
vn -0.90390000 0.11430000 0.41210000
|
| 1561 |
+
vn -0.89500000 0.10460000 0.43370000
|
| 1562 |
+
vn -0.99310000 0.11740000 0.00080000
|
| 1563 |
+
vn -0.99310000 0.11740000 0.00080000
|
| 1564 |
+
vn -0.99640000 0.08440000 0.00210000
|
| 1565 |
+
vn -0.99210000 -0.12510000 -0.00020000
|
| 1566 |
+
vn -0.93490000 -0.08820000 0.34390000
|
| 1567 |
+
vn -0.89230000 -0.12140000 0.43480000
|
| 1568 |
+
vn -0.90390000 0.11430000 0.41210000
|
| 1569 |
+
vn -0.55630000 -0.72100000 0.41320000
|
| 1570 |
+
vn -0.40950000 -0.75150000 0.51730000
|
| 1571 |
+
vn -0.61100000 -0.79160000 0.00010000
|
| 1572 |
+
vn -0.48630000 -0.87380000 0.00050000
|
| 1573 |
+
vn -0.30490000 -0.95240000 -0.00050000
|
| 1574 |
+
vn -0.28990000 -0.86180000 0.41630000
|
| 1575 |
+
vn -0.41910000 -0.90790000 0.00250000
|
| 1576 |
+
vn -0.48630000 -0.87380000 0.00050000
|
| 1577 |
+
vn -0.28230000 -0.85800000 0.42920000
|
| 1578 |
+
vn -0.40950000 -0.75150000 0.51730000
|
| 1579 |
+
vn 0.71530000 -0.61860000 0.32520000
|
| 1580 |
+
vn 0.66980000 -0.74250000 0.00080000
|
| 1581 |
+
vn 0.79650000 -0.60460000 -0.00070000
|
| 1582 |
+
vn 0.71060000 -0.70360000 0.00240000
|
| 1583 |
+
vn 0.56740000 -0.64060000 0.51750000
|
| 1584 |
+
vn 0.71450000 -0.55620000 0.42440000
|
| 1585 |
+
vn 0.53610000 -0.84420000 0.00010000
|
| 1586 |
+
vn 0.66980000 -0.74250000 0.00080000
|
| 1587 |
+
vn 0.49210000 -0.76310000 0.41900000
|
| 1588 |
+
vn 0.56740000 -0.64060000 0.51750000
|
| 1589 |
+
vn 0.99210000 0.12570000 0.00240000
|
| 1590 |
+
vn 0.92810000 0.06680000 0.36620000
|
| 1591 |
+
vn 0.99830000 -0.05830000 0.00020000
|
| 1592 |
+
vn 0.83190000 0.17240000 0.52750000
|
| 1593 |
+
vn 0.85010000 -0.03950000 0.52510000
|
| 1594 |
+
vn 0.97850000 0.20640000 0.00000000
|
| 1595 |
+
vn 0.85010000 -0.03950000 0.52510000
|
| 1596 |
+
vn 0.97370000 -0.22800000 -0.00020000
|
| 1597 |
+
vn 0.99830000 -0.05830000 0.00020000
|
| 1598 |
+
vn 0.99250000 -0.12220000 0.00170000
|
| 1599 |
+
vn 0.87650000 -0.20730000 0.43460000
|
| 1600 |
+
vn 0.90910000 -0.41660000 0.00090000
|
| 1601 |
+
vn 0.87650000 -0.20730000 0.43460000
|
| 1602 |
+
vn 0.85590000 -0.31560000 0.40960000
|
| 1603 |
+
vn 0.90400000 -0.26610000 0.33470000
|
| 1604 |
+
vn 0.97370000 -0.22800000 -0.00020000
|
| 1605 |
+
vn 0.90910000 -0.41660000 0.00090000
|
| 1606 |
+
vn 0.79650000 -0.60460000 -0.00070000
|
| 1607 |
+
vn 0.90360000 -0.42840000 0.00150000
|
| 1608 |
+
vn 0.84280000 -0.48570000 0.23180000
|
| 1609 |
+
vn 0.85590000 -0.31560000 0.40960000
|
| 1610 |
+
vn 0.71530000 -0.61860000 0.32520000
|
| 1611 |
+
vn 0.39270000 -0.91970000 0.00040000
|
| 1612 |
+
vn 0.33210000 -0.78740000 0.51930000
|
| 1613 |
+
vn 0.49460000 -0.75200000 0.43580000
|
| 1614 |
+
vn 0.45680000 -0.88960000 0.00190000
|
| 1615 |
+
vn 0.53610000 -0.84420000 0.00010000
|
| 1616 |
+
vn 0.49210000 -0.76310000 0.41900000
|
| 1617 |
+
vn 0.12700000 -0.89450000 0.42860000
|
| 1618 |
+
vn 0.33210000 -0.78740000 0.51930000
|
| 1619 |
+
vn 0.39270000 -0.91970000 0.00040000
|
| 1620 |
+
vn 0.22900000 -0.91350000 0.33630000
|
| 1621 |
+
vn 0.22340000 -0.97470000 0.00230000
|
| 1622 |
+
vn 0.13780000 -0.99050000 -0.00030000
|
| 1623 |
+
vn 0.11240000 -0.91180000 0.39500000
|
| 1624 |
+
vn -0.07170000 -0.99740000 0.00110000
|
| 1625 |
+
vn -0.04900000 -0.85460000 0.51700000
|
| 1626 |
+
vn 0.12700000 -0.89450000 0.42860000
|
| 1627 |
+
vn 0.13780000 -0.99050000 -0.00030000
|
| 1628 |
+
vn -0.07170000 -0.99740000 0.00110000
|
| 1629 |
+
vn -0.04900000 -0.85460000 0.51700000
|
| 1630 |
+
vn -0.30490000 -0.95240000 -0.00050000
|
| 1631 |
+
vn -0.09300000 -0.99570000 0.00200000
|
| 1632 |
+
vn -0.21550000 -0.91260000 0.34750000
|
| 1633 |
+
vn -0.28990000 -0.86180000 0.41630000
|
| 1634 |
+
vn -0.61100000 -0.79160000 0.00010000
|
| 1635 |
+
vn -0.73290000 -0.68040000 0.00030000
|
| 1636 |
+
vn -0.55630000 -0.72100000 0.41320000
|
| 1637 |
+
vn -0.62880000 -0.57860000 0.51940000
|
| 1638 |
+
vn -0.68030000 -0.73300000 0.00190000
|
| 1639 |
+
vn -0.54030000 -0.71910000 0.43700000
|
| 1640 |
+
vn -0.79920000 -0.42410000 0.42600000
|
| 1641 |
+
vn -0.73290000 -0.68040000 0.00030000
|
| 1642 |
+
vn -0.62880000 -0.57860000 0.51940000
|
| 1643 |
+
vn -0.88500000 -0.46560000 -0.00040000
|
| 1644 |
+
vn -0.78180000 -0.52480000 0.33660000
|
| 1645 |
+
vn -0.83940000 -0.54360000 0.00240000
|
| 1646 |
+
vn -0.95230000 -0.30510000 0.00080000
|
| 1647 |
+
vn -0.79920000 -0.42410000 0.42600000
|
| 1648 |
+
vn -0.81610000 -0.41770000 0.39950000
|
| 1649 |
+
vn -0.81870000 -0.25350000 0.51530000
|
| 1650 |
+
vn -0.88500000 -0.46560000 -0.00040000
|
| 1651 |
+
vn -0.89230000 -0.12140000 0.43480000
|
| 1652 |
+
vn -0.96820000 -0.25040000 0.00250000
|
| 1653 |
+
vn -0.81870000 -0.25350000 0.51530000
|
| 1654 |
+
vn -0.95230000 -0.30510000 0.00080000
|
| 1655 |
+
vn -0.99210000 -0.12510000 -0.00020000
|
| 1656 |
+
vn -0.79680000 0.60430000 -0.00060000
|
| 1657 |
+
vn -0.81310000 0.41010000 0.41310000
|
| 1658 |
+
vn -0.89460000 0.44680000 0.00150000
|
| 1659 |
+
vn -0.68990000 0.50410000 0.51950000
|
| 1660 |
+
vn -0.81090000 0.40300000 0.42440000
|
| 1661 |
+
vn -0.66370000 0.66840000 0.33580000
|
| 1662 |
+
vn -0.79680000 0.60430000 -0.00060000
|
| 1663 |
+
vn -0.56750000 0.71190000 0.41370000
|
| 1664 |
+
vn -0.63080000 0.77600000 -0.00020000
|
| 1665 |
+
vn -0.68990000 0.50410000 0.51950000
|
| 1666 |
+
vn -0.70060000 0.71360000 0.00270000
|
| 1667 |
+
vn -0.63080000 0.77600000 -0.00020000
|
| 1668 |
+
vn -0.41040000 0.75450000 0.51210000
|
| 1669 |
+
vn -0.56750000 0.71190000 0.41370000
|
| 1670 |
+
vn -0.56580000 0.72170000 0.39890000
|
| 1671 |
+
vn -0.47800000 0.87840000 0.00060000
|
| 1672 |
+
vn -0.47800000 0.87840000 0.00060000
|
| 1673 |
+
vn -0.34250000 0.93950000 0.00040000
|
| 1674 |
+
vn -0.30010000 0.84370000 0.44510000
|
| 1675 |
+
vn -0.41040000 0.75450000 0.51210000
|
| 1676 |
+
vn -0.41890000 0.90800000 0.00240000
|
| 1677 |
+
vn 0.11820000 0.99300000 -0.00060000
|
| 1678 |
+
vn 0.10830000 0.87500000 0.47180000
|
| 1679 |
+
vn 0.24100000 0.81850000 0.52150000
|
| 1680 |
+
vn 0.29890000 0.95430000 0.00180000
|
| 1681 |
+
vn 0.12860000 0.88540000 0.44670000
|
| 1682 |
+
vn 0.24100000 0.81850000 0.52150000
|
| 1683 |
+
vn 0.47750000 0.77410000 0.41560000
|
| 1684 |
+
vn 0.40760000 0.84840000 0.33770000
|
| 1685 |
+
vn 0.29890000 0.95430000 0.00180000
|
| 1686 |
+
vn 0.51720000 0.85580000 -0.00030000
|
| 1687 |
+
vn 0.34810000 0.93740000 0.00420000
|
| 1688 |
+
vn 0.37790000 0.92580000 0.00450000
|
| 1689 |
+
vn 0.51720000 0.85580000 -0.00030000
|
| 1690 |
+
vn 0.57390000 0.63660000 0.51510000
|
| 1691 |
+
vn 0.48930000 0.77600000 0.39800000
|
| 1692 |
+
vn 0.47750000 0.77410000 0.41560000
|
| 1693 |
+
vn 0.66240000 0.74920000 0.00060000
|
| 1694 |
+
vn 0.72400000 0.54550000 0.42220000
|
| 1695 |
+
vn 0.66240000 0.74920000 0.00060000
|
| 1696 |
+
vn 0.73530000 0.61600000 0.28280000
|
| 1697 |
+
vn 0.57390000 0.63660000 0.51510000
|
| 1698 |
+
vn 0.71080000 0.70340000 0.00250000
|
| 1699 |
+
vn 0.79760000 0.60320000 -0.00050000
|
| 1700 |
+
vn -0.89460000 0.44680000 0.00150000
|
| 1701 |
+
vn -0.81450000 0.25780000 0.51970000
|
| 1702 |
+
vn -0.81310000 0.41010000 0.41310000
|
| 1703 |
+
vn -0.90810000 0.41880000 0.00260000
|
| 1704 |
+
vn -0.95060000 0.31050000 0.00020000
|
| 1705 |
+
vn -0.30010000 0.84370000 0.44510000
|
| 1706 |
+
vn -0.29610000 0.85110000 0.43350000
|
| 1707 |
+
vn -0.18050000 0.98360000 0.00040000
|
| 1708 |
+
vn -0.34250000 0.93950000 0.00040000
|
| 1709 |
+
vn -0.16220000 0.84220000 0.51420000
|
| 1710 |
+
vn -0.05870000 0.87340000 0.48340000
|
| 1711 |
+
vn 0.10830000 0.87500000 0.47180000
|
| 1712 |
+
vn -0.02910000 0.90440000 0.42570000
|
| 1713 |
+
vn 0.11820000 0.99300000 -0.00060000
|
| 1714 |
+
vn -0.03200000 0.99950000 0.00110000
|
| 1715 |
+
vn 0.91110000 0.41230000 0.00100000
|
| 1716 |
+
vn 0.83190000 0.17240000 0.52750000
|
| 1717 |
+
vn 0.97850000 0.20640000 0.00000000
|
| 1718 |
+
vn 0.82720000 0.37280000 0.42050000
|
| 1719 |
+
vn 0.88990000 0.35180000 0.29040000
|
| 1720 |
+
vn 0.00010000 -0.00010000 1.00000000
|
| 1721 |
+
vn 0.71060000 -0.70360000 0.00240000
|
| 1722 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1723 |
+
vn 0.79650000 -0.60460000 -0.00070000
|
| 1724 |
+
vn 0.90360000 -0.42840000 0.00150000
|
| 1725 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1726 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1727 |
+
vn 0.00010000 -0.00000000 1.00000000
|
| 1728 |
+
vn 0.00030000 -0.00000000 1.00000000
|
| 1729 |
+
vn 0.90360000 -0.42840000 0.00150000
|
| 1730 |
+
vn 0.90910000 -0.41660000 0.00090000
|
| 1731 |
+
vn 0.99250000 -0.12220000 0.00170000
|
| 1732 |
+
vn 0.00010000 -0.00010000 1.00000000
|
| 1733 |
+
vn 0.97370000 -0.22800000 -0.00020000
|
| 1734 |
+
vn 0.99250000 -0.12220000 0.00170000
|
| 1735 |
+
vn 0.99210000 0.12570000 0.00240000
|
| 1736 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1737 |
+
vn 0.99830000 -0.05830000 0.00020000
|
| 1738 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1739 |
+
vn 0.90370000 0.42810000 0.00170000
|
| 1740 |
+
vn 0.91110000 0.41230000 0.00100000
|
| 1741 |
+
vn 0.97850000 0.20640000 0.00000000
|
| 1742 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1743 |
+
vn 0.99210000 0.12570000 0.00240000
|
| 1744 |
+
vn 0.71080000 0.70340000 0.00250000
|
| 1745 |
+
vn 0.00010000 0.00010000 1.00000000
|
| 1746 |
+
vn 0.90370000 0.42810000 0.00170000
|
| 1747 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1748 |
+
vn 0.79760000 0.60320000 -0.00050000
|
| 1749 |
+
vn 0.66240000 0.74920000 0.00060000
|
| 1750 |
+
vn 0.51720000 0.85580000 -0.00030000
|
| 1751 |
+
vn 0.71080000 0.70340000 0.00250000
|
| 1752 |
+
vn 0.37790000 0.92580000 0.00450000
|
| 1753 |
+
vn 0.00010000 0.00010000 1.00000000
|
| 1754 |
+
vn 0.00000000 -0.00020000 1.00000000
|
| 1755 |
+
vn 0.34810000 0.93740000 0.00420000
|
| 1756 |
+
vn 0.11820000 0.99300000 -0.00060000
|
| 1757 |
+
vn 0.29890000 0.95430000 0.00180000
|
| 1758 |
+
vn 0.00000000 -0.00020000 1.00000000
|
| 1759 |
+
vn -0.00000000 -0.00010000 1.00000000
|
| 1760 |
+
vn -0.00010000 -0.00040000 1.00000000
|
| 1761 |
+
vn 0.00000000 -0.00050000 1.00000000
|
| 1762 |
+
vn -0.08000000 0.99680000 0.00270000
|
| 1763 |
+
vn -0.03200000 0.99950000 0.00110000
|
| 1764 |
+
vn -0.00000000 -0.00010000 1.00000000
|
| 1765 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1766 |
+
vn -0.34250000 0.93950000 0.00040000
|
| 1767 |
+
vn -0.18050000 0.98360000 0.00040000
|
| 1768 |
+
vn -0.41890000 0.90800000 0.00240000
|
| 1769 |
+
vn -0.08000000 0.99680000 0.00270000
|
| 1770 |
+
vn -0.00010000 0.00010000 1.00000000
|
| 1771 |
+
vn -0.70060000 0.71360000 0.00270000
|
| 1772 |
+
vn -0.47800000 0.87840000 0.00060000
|
| 1773 |
+
vn -0.00010000 0.00010000 1.00000000
|
| 1774 |
+
vn -0.00010000 0.00020000 1.00000000
|
| 1775 |
+
vn -0.41890000 0.90800000 0.00240000
|
| 1776 |
+
vn -0.63080000 0.77600000 -0.00020000
|
| 1777 |
+
vn -0.00030000 0.00020000 1.00000000
|
| 1778 |
+
vn -0.00010000 0.00010000 1.00000000
|
| 1779 |
+
vn -0.70060000 0.71360000 0.00270000
|
| 1780 |
+
vn -0.00030000 0.00020000 1.00000000
|
| 1781 |
+
vn -0.00020000 0.00010000 1.00000000
|
| 1782 |
+
vn -0.00040000 0.00020000 1.00000000
|
| 1783 |
+
vn -0.90810000 0.41880000 0.00260000
|
| 1784 |
+
vn -0.79680000 0.60430000 -0.00060000
|
| 1785 |
+
vn -0.89460000 0.44680000 0.00150000
|
| 1786 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1787 |
+
vn -0.99640000 0.08440000 0.00210000
|
| 1788 |
+
vn -0.99310000 0.11740000 0.00080000
|
| 1789 |
+
vn -0.90810000 0.41880000 0.00260000
|
| 1790 |
+
vn -0.95060000 0.31050000 0.00020000
|
| 1791 |
+
vn 0.00010000 -0.00000000 1.00000000
|
| 1792 |
+
vn -0.00010000 0.00010000 1.00000000
|
| 1793 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1794 |
+
vn 0.00010000 -0.00000000 1.00000000
|
| 1795 |
+
vn -0.99210000 -0.12510000 -0.00020000
|
| 1796 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1797 |
+
vn -0.99640000 0.08440000 0.00210000
|
| 1798 |
+
vn -0.00020000 -0.00000000 1.00000000
|
| 1799 |
+
vn -0.96820000 -0.25040000 0.00250000
|
| 1800 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1801 |
+
vn -0.83940000 -0.54360000 0.00240000
|
| 1802 |
+
vn -0.88500000 -0.46560000 -0.00040000
|
| 1803 |
+
vn -0.00020000 -0.00000000 1.00000000
|
| 1804 |
+
vn -0.95230000 -0.30510000 0.00080000
|
| 1805 |
+
vn -0.00030000 -0.00010000 1.00000000
|
| 1806 |
+
vn -0.00010000 0.00000000 1.00000000
|
| 1807 |
+
vn -0.96820000 -0.25040000 0.00250000
|
| 1808 |
+
vn -0.83940000 -0.54360000 0.00240000
|
| 1809 |
+
vn -0.73290000 -0.68040000 0.00030000
|
| 1810 |
+
vn -0.68030000 -0.73300000 0.00190000
|
| 1811 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1812 |
+
vn -0.41910000 -0.90790000 0.00250000
|
| 1813 |
+
vn -0.48630000 -0.87380000 0.00050000
|
| 1814 |
+
vn -0.68030000 -0.73300000 0.00190000
|
| 1815 |
+
vn -0.61100000 -0.79160000 0.00010000
|
| 1816 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1817 |
+
vn 0.00000000 -0.00020000 1.00000000
|
| 1818 |
+
vn -0.09300000 -0.99570000 0.00200000
|
| 1819 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1820 |
+
vn -0.41910000 -0.90790000 0.00250000
|
| 1821 |
+
vn -0.30490000 -0.95240000 -0.00050000
|
| 1822 |
+
vn -0.07170000 -0.99740000 0.00110000
|
| 1823 |
+
vn 0.13780000 -0.99050000 -0.00030000
|
| 1824 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1825 |
+
vn 0.00000000 -0.00020000 1.00000000
|
| 1826 |
+
vn 0.22340000 -0.97470000 0.00230000
|
| 1827 |
+
vn -0.00000000 -0.00010000 1.00000000
|
| 1828 |
+
vn 0.00010000 -0.00020000 1.00000000
|
| 1829 |
+
vn -0.09300000 -0.99570000 0.00200000
|
| 1830 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1831 |
+
vn 0.39270000 -0.91970000 0.00040000
|
| 1832 |
+
vn 0.45680000 -0.88960000 0.00190000
|
| 1833 |
+
vn 0.22340000 -0.97470000 0.00230000
|
| 1834 |
+
vn 0.45680000 -0.88960000 0.00190000
|
| 1835 |
+
vn 0.53610000 -0.84420000 0.00010000
|
| 1836 |
+
vn 0.00000000 0.00000000 1.00000000
|
| 1837 |
+
vn 0.66980000 -0.74250000 0.00080000
|
| 1838 |
+
vn 0.71060000 -0.70360000 0.00240000
|
| 1839 |
+
f 239//239 70//70 69//69
|
| 1840 |
+
f 71//71 240//240 299//299
|
| 1841 |
+
f 72//72 297//297 74//74
|
| 1842 |
+
f 73//73 298//298 282//282
|
| 1843 |
+
f 75//75 286//286 78//78
|
| 1844 |
+
f 77//77 284//284 293//293
|
| 1845 |
+
f 76//76 289//289 80//80
|
| 1846 |
+
f 79//79 290//290 83//83
|
| 1847 |
+
f 82//82 292//292 246//246
|
| 1848 |
+
f 245//245 250//250 81//81
|
| 1849 |
+
f 84//84 251//251 87//87
|
| 1850 |
+
f 85//85 252//252 279//279
|
| 1851 |
+
f 86//86 281//281 88//88
|
| 1852 |
+
f 89//89 277//277 267//267
|
| 1853 |
+
f 90//90 268//268 91//91
|
| 1854 |
+
f 92//92 269//269 276//276
|
| 1855 |
+
f 93//93 275//275 95//95
|
| 1856 |
+
f 94//94 273//273 99//99
|
| 1857 |
+
f 98//98 271//271 256//256
|
| 1858 |
+
f 257//257 258//258 97//97
|
| 1859 |
+
f 96//96 260//260 101//101
|
| 1860 |
+
f 100//100 262//262 139//139
|
| 1861 |
+
f 102//102 136//136 104//104
|
| 1862 |
+
f 105//105 140//140 384//384
|
| 1863 |
+
f 103//103 382//382 108//108
|
| 1864 |
+
f 107//107 383//383 145//145
|
| 1865 |
+
f 106//106 146//146 110//110
|
| 1866 |
+
f 109//109 141//141 112//112
|
| 1867 |
+
f 111//111 143//143 147//147
|
| 1868 |
+
f 150//150 153//153 113//113
|
| 1869 |
+
f 114//114 152//152 115//115
|
| 1870 |
+
f 116//116 156//156 377//377
|
| 1871 |
+
f 117//117 374//374 118//118
|
| 1872 |
+
f 119//119 378//378 369//369
|
| 1873 |
+
f 120//120 371//371 123//123
|
| 1874 |
+
f 122//122 370//370 159//159
|
| 1875 |
+
f 121//121 161//161 124//124
|
| 1876 |
+
f 125//125 160//160 128//128
|
| 1877 |
+
f 129//129 163//163 165//165
|
| 1878 |
+
f 164//164 169//169 127//127
|
| 1879 |
+
f 126//126 170//170 130//130
|
| 1880 |
+
f 132//132 171//171 364//364
|
| 1881 |
+
f 131//131 363//363 135//135
|
| 1882 |
+
f 134//134 365//365 357//357
|
| 1883 |
+
f 133//133 362//362 1//1
|
| 1884 |
+
f 2//2 359//359 178//178
|
| 1885 |
+
f 3//3 177//177 4//4
|
| 1886 |
+
f 5//5 180//180 6//6
|
| 1887 |
+
f 7//7 179//179 183//183
|
| 1888 |
+
f 182//182 186//186 8//8
|
| 1889 |
+
f 9//9 187//187 12//12
|
| 1890 |
+
f 11//11 185//185 352//352
|
| 1891 |
+
f 10//10 353//353 15//15
|
| 1892 |
+
f 14//14 354//354 349//349
|
| 1893 |
+
f 13//13 351//351 16//16
|
| 1894 |
+
f 18//18 350//350 192//192
|
| 1895 |
+
f 17//17 191//191 19//19
|
| 1896 |
+
f 20//20 195//195 24//24
|
| 1897 |
+
f 23//23 193//193 199//199
|
| 1898 |
+
f 22//22 200//200 204//204
|
| 1899 |
+
f 21//21 205//205 25//25
|
| 1900 |
+
f 26//26 206//206 343//343
|
| 1901 |
+
f 27//27 342//342 28//28
|
| 1902 |
+
f 30//30 341//341 330//330
|
| 1903 |
+
f 29//29 331//331 32//32
|
| 1904 |
+
f 31//31 332//332 338//338
|
| 1905 |
+
f 33//33 337//337 35//35
|
| 1906 |
+
f 34//34 336//336 36//36
|
| 1907 |
+
f 39//39 339//339 209//209
|
| 1908 |
+
f 210//210 214//214 38//38
|
| 1909 |
+
f 37//37 212//212 41//41
|
| 1910 |
+
f 40//40 211//211 327//327
|
| 1911 |
+
f 42//42 326//326 43//43
|
| 1912 |
+
f 45//45 324//324 322//322
|
| 1913 |
+
f 44//44 321//321 46//46
|
| 1914 |
+
f 48//48 318//318 218//218
|
| 1915 |
+
f 47//47 223//223 50//50
|
| 1916 |
+
f 49//49 219//219 51//51
|
| 1917 |
+
f 52//52 220//220 225//225
|
| 1918 |
+
f 228//228 229//229 53//53
|
| 1919 |
+
f 54//54 230//230 57//57
|
| 1920 |
+
f 55//55 231//231 315//315
|
| 1921 |
+
f 56//56 314//314 59//59
|
| 1922 |
+
f 58//58 313//313 300//300
|
| 1923 |
+
f 60//60 301//301 61//61
|
| 1924 |
+
f 63//63 302//302 306//306
|
| 1925 |
+
f 62//62 305//305 64//64
|
| 1926 |
+
f 65//65 311//311 66//66
|
| 1927 |
+
f 67//67 307//307 234//234
|
| 1928 |
+
f 68//68 238//238 241//241
|
| 1929 |
+
f 312//312 385//385 304//304
|
| 1930 |
+
f 303//303 387//387 308//308
|
| 1931 |
+
f 309//309 388//388 394//394
|
| 1932 |
+
f 310//310 397//397 237//237
|
| 1933 |
+
f 236//236 393//393 399//399
|
| 1934 |
+
f 235//235 402//402 242//242
|
| 1935 |
+
f 243//243 398//398 296//296
|
| 1936 |
+
f 295//295 400//400 285//285
|
| 1937 |
+
f 283//283 401//401 407//407
|
| 1938 |
+
f 287//287 410//410 418//418
|
| 1939 |
+
f 288//288 411//411 291//291
|
| 1940 |
+
f 294//294 412//412 247//247
|
| 1941 |
+
f 244//244 413//413 248//248
|
| 1942 |
+
f 249//249 419//419 422//422
|
| 1943 |
+
f 253//253 425//425 278//278
|
| 1944 |
+
f 389//389 316//316 432//432
|
| 1945 |
+
f 430//430 317//317 233//233
|
| 1946 |
+
f 427//427 232//232 227//227
|
| 1947 |
+
f 431//431 226//226 224//224
|
| 1948 |
+
f 434//434 221//221 436//436
|
| 1949 |
+
f 440//440 222//222 447//447
|
| 1950 |
+
f 444//444 217//217 319//319
|
| 1951 |
+
f 441//441 320//320 325//325
|
| 1952 |
+
f 448//448 323//323 213//213
|
| 1953 |
+
f 443//443 216//216 449//449
|
| 1954 |
+
f 455//455 215//215 207//207
|
| 1955 |
+
f 344//344 461//461 328//328
|
| 1956 |
+
f 329//329 458//458 333//333
|
| 1957 |
+
f 334//334 459//459 450//450
|
| 1958 |
+
f 335//335 456//456 208//208
|
| 1959 |
+
f 367//367 522//522 360//360
|
| 1960 |
+
f 358//358 524//524 469//469
|
| 1961 |
+
f 361//361 465//465 176//176
|
| 1962 |
+
f 174//174 467//467 471//471
|
| 1963 |
+
f 175//175 470//470 184//184
|
| 1964 |
+
f 181//181 472//472 188//188
|
| 1965 |
+
f 189//189 473//473 477//477
|
| 1966 |
+
f 190//190 479//479 355//355
|
| 1967 |
+
f 356//356 482//482 346//346
|
| 1968 |
+
f 348//348 483//483 489//489
|
| 1969 |
+
f 347//347 484//484 194//194
|
| 1970 |
+
f 196//196 490//490 197//197
|
| 1971 |
+
f 201//201 486//486 495//495
|
| 1972 |
+
f 198//198 494//494 202//202
|
| 1973 |
+
f 203//203 491//491 340//340
|
| 1974 |
+
f 345//345 492//492 462//462
|
| 1975 |
+
f 142//142 555//555 148//148
|
| 1976 |
+
f 151//151 557//557 504//504
|
| 1977 |
+
f 149//149 499//499 155//155
|
| 1978 |
+
f 154//154 505//505 376//376
|
| 1979 |
+
f 375//375 500//500 368//368
|
| 1980 |
+
f 372//372 501//501 511//511
|
| 1981 |
+
f 373//373 509//509 158//158
|
| 1982 |
+
f 157//157 510//510 516//516
|
| 1983 |
+
f 162//162 515//515 167//167
|
| 1984 |
+
f 166//166 517//517 172//172
|
| 1985 |
+
f 173//173 513//513 521//521
|
| 1986 |
+
f 168//168 523//523 366//366
|
| 1987 |
+
f 280//280 421//421 266//266
|
| 1988 |
+
f 265//265 420//420 531//531
|
| 1989 |
+
f 264//264 530//530 272//272
|
| 1990 |
+
f 274//274 529//529 540//540
|
| 1991 |
+
f 270//270 539//539 254//254
|
| 1992 |
+
f 255//255 542//542 259//259
|
| 1993 |
+
f 261//261 541//541 544//544
|
| 1994 |
+
f 263//263 543//543 138//138
|
| 1995 |
+
f 137//137 547//547 379//379
|
| 1996 |
+
f 380//380 545//545 556//556
|
| 1997 |
+
f 381//381 550//550 144//144
|
| 1998 |
+
f 460//460 496//496 798//798
|
| 1999 |
+
f 457//457 796//796 672//672
|
| 2000 |
+
f 451//451 463//463 670//670
|
| 2001 |
+
f 453//453 673//673 675//675
|
| 2002 |
+
f 435//435 437//437 664//664
|
| 2003 |
+
f 428//428 663//663 668//668
|
| 2004 |
+
f 429//429 667//667 696//696
|
| 2005 |
+
f 386//386 700//700 396//396
|
| 2006 |
+
f 416//416 409//409 657//657
|
| 2007 |
+
f 417//417 658//658 650//650
|
| 2008 |
+
f 414//414 649//649 716//716
|
| 2009 |
+
f 424//424 724//724 533//533
|
| 2010 |
+
f 552//552 782//782 737//737
|
| 2011 |
+
f 503//503 741//741 507//507
|
| 2012 |
+
f 466//466 528//528 790//790
|
| 2013 |
+
f 464//464 791//791 758//758
|
| 2014 |
+
f 476//476 764//764 478//478
|
| 2015 |
+
f 452//452 679//679 681//681
|
| 2016 |
+
f 445//445 682//682 689//689
|
| 2017 |
+
f 442//442 454//454 683//683
|
| 2018 |
+
f 439//439 446//446 688//688
|
| 2019 |
+
f 438//438 690//690 659//659
|
| 2020 |
+
f 697//697 706//706 395//395
|
| 2021 |
+
f 692//692 698//698 391//391
|
| 2022 |
+
f 693//693 390//390 433//433
|
| 2023 |
+
f 405//405 392//392 703//703
|
| 2024 |
+
f 403//403 705//705 709//709
|
| 2025 |
+
f 408//408 713//713 654//654
|
| 2026 |
+
f 404//404 712//712 406//406
|
| 2027 |
+
f 720//720 727//727 534//534
|
| 2028 |
+
f 717//717 722//722 423//423
|
| 2029 |
+
f 719//719 426//426 415//415
|
| 2030 |
+
f 538//538 532//532 728//728
|
| 2031 |
+
f 537//537 729//729 733//733
|
| 2032 |
+
f 536//536 731//731 647//647
|
| 2033 |
+
f 546//546 648//648 640//640
|
| 2034 |
+
f 646//646 548//548 535//535
|
| 2035 |
+
f 639//639 781//781 551//551
|
| 2036 |
+
f 641//641 553//553 549//549
|
| 2037 |
+
f 743//743 749//749 512//512
|
| 2038 |
+
f 739//739 745//745 506//506
|
| 2039 |
+
f 740//740 502//502 554//554
|
| 2040 |
+
f 514//514 508//508 750//750
|
| 2041 |
+
f 518//518 748//748 755//755
|
| 2042 |
+
f 754//754 785//785 519//519
|
| 2043 |
+
f 527//527 520//520 786//786
|
| 2044 |
+
f 526//526 789//789 636//636
|
| 2045 |
+
f 637//637 792//792 525//525
|
| 2046 |
+
f 763//763 772//772 480//480
|
| 2047 |
+
f 759//759 762//762 475//475
|
| 2048 |
+
f 761//761 474//474 468//468
|
| 2049 |
+
f 488//488 481//481 771//771
|
| 2050 |
+
f 487//487 770//770 777//777
|
| 2051 |
+
f 497//497 776//776 629//629
|
| 2052 |
+
f 631//631 799//799 498//498
|
| 2053 |
+
f 774//774 493//493 485//485
|
| 2054 |
+
f 567//567 805//805 565//565
|
| 2055 |
+
f 564//564 800//800 812//812
|
| 2056 |
+
f 563//563 807//807 558//558
|
| 2057 |
+
f 559//559 808//808 562//562
|
| 2058 |
+
f 561//561 806//806 818//818
|
| 2059 |
+
f 560//560 816//816 627//627
|
| 2060 |
+
f 627//627 816//816 822//822
|
| 2061 |
+
f 627//627 822//822 626//626
|
| 2062 |
+
f 626//626 822//822 624//624
|
| 2063 |
+
f 624//624 822//822 827//827
|
| 2064 |
+
f 624//624 827//827 625//625
|
| 2065 |
+
f 625//625 827//827 622//622
|
| 2066 |
+
f 623//623 825//825 833//833
|
| 2067 |
+
f 623//623 833//833 620//620
|
| 2068 |
+
f 621//621 834//834 616//616
|
| 2069 |
+
f 614//614 619//619 840//840
|
| 2070 |
+
f 615//615 838//838 612//612
|
| 2071 |
+
f 613//613 841//841 610//610
|
| 2072 |
+
f 611//611 839//839 844//844
|
| 2073 |
+
f 609//609 845//845 608//608
|
| 2074 |
+
f 608//608 845//845 604//604
|
| 2075 |
+
f 605//605 850//850 853//853
|
| 2076 |
+
f 605//605 853//853 606//606
|
| 2077 |
+
f 607//607 854//854 603//603
|
| 2078 |
+
f 601//601 857//857 860//860
|
| 2079 |
+
f 602//602 861//861 600//600
|
| 2080 |
+
f 599//599 862//862 597//597
|
| 2081 |
+
f 596//596 858//858 872//872
|
| 2082 |
+
f 598//598 873//873 595//595
|
| 2083 |
+
f 594//594 866//866 592//592
|
| 2084 |
+
f 593//593 871//871 874//874
|
| 2085 |
+
f 591//591 876//876 590//590
|
| 2086 |
+
f 589//589 874//874 588//588
|
| 2087 |
+
f 586//586 878//878 883//883
|
| 2088 |
+
f 587//587 886//886 582//582
|
| 2089 |
+
f 583//583 885//885 585//585
|
| 2090 |
+
f 584//584 880//880 891//891
|
| 2091 |
+
f 584//584 891//891 581//581
|
| 2092 |
+
f 581//581 891//891 896//896
|
| 2093 |
+
f 581//581 896//896 580//580
|
| 2094 |
+
f 580//580 896//896 579//579
|
| 2095 |
+
f 579//579 896//896 899//899
|
| 2096 |
+
f 579//579 899//899 578//578
|
| 2097 |
+
f 578//578 899//899 575//575
|
| 2098 |
+
f 576//576 897//897 905//905
|
| 2099 |
+
f 577//577 907//907 573//573
|
| 2100 |
+
f 574//574 908//908 572//572
|
| 2101 |
+
f 571//571 904//904 910//910
|
| 2102 |
+
f 571//571 910//910 569//569
|
| 2103 |
+
f 569//569 910//910 916//916
|
| 2104 |
+
f 569//569 916//916 570//570
|
| 2105 |
+
f 570//570 916//916 568//568
|
| 2106 |
+
f 568//568 916//916 802//802
|
| 2107 |
+
f 568//568 802//802 566//566
|
| 2108 |
+
f 909//909 898//898 711//711
|
| 2109 |
+
f 892//892 655//655 900//900
|
| 2110 |
+
f 901//901 653//653 710//710
|
| 2111 |
+
f 893//893 652//652 656//656
|
| 2112 |
+
f 889//889 721//721 715//715
|
| 2113 |
+
f 890//890 718//718 894//894
|
| 2114 |
+
f 895//895 714//714 651//651
|
| 2115 |
+
f 882//882 730//730 723//723
|
| 2116 |
+
f 881//881 725//725 888//888
|
| 2117 |
+
f 879//879 732//732 887//887
|
| 2118 |
+
f 884//884 734//734 726//726
|
| 2119 |
+
f 875//875 645//645 735//735
|
| 2120 |
+
f 867//867 644//644 877//877
|
| 2121 |
+
f 868//868 642//642 643//643
|
| 2122 |
+
f 863//863 783//783 869//869
|
| 2123 |
+
f 870//870 784//784 638//638
|
| 2124 |
+
f 742//742 736//736 864//864
|
| 2125 |
+
f 865//865 738//738 780//780
|
| 2126 |
+
f 856//856 747//747 744//744
|
| 2127 |
+
f 851//851 746//746 859//859
|
| 2128 |
+
f 848//848 756//756 855//855
|
| 2129 |
+
f 852//852 752//752 751//751
|
| 2130 |
+
f 846//846 788//788 753//753
|
| 2131 |
+
f 842//842 634//634 849//849
|
| 2132 |
+
f 847//847 633//633 787//787
|
| 2133 |
+
f 843//843 794//794 635//635
|
| 2134 |
+
f 765//765 760//760 837//837
|
| 2135 |
+
f 836//836 757//757 793//793
|
| 2136 |
+
f 767//767 835//835 617//617
|
| 2137 |
+
f 768//768 618//618 832//832
|
| 2138 |
+
f 766//766 830//830 769//769
|
| 2139 |
+
f 773//773 829//829 775//775
|
| 2140 |
+
f 778//778 831//831 824//824
|
| 2141 |
+
f 779//779 828//828 632//632
|
| 2142 |
+
f 628//628 826//826 819//819
|
| 2143 |
+
f 630//630 820//820 795//795
|
| 2144 |
+
f 797//797 821//821 674//674
|
| 2145 |
+
f 669//669 823//823 815//815
|
| 2146 |
+
f 813//813 684//684 676//676
|
| 2147 |
+
f 811//811 678//678 814//814
|
| 2148 |
+
f 817//817 677//677 671//671
|
| 2149 |
+
f 804//804 687//687 809//809
|
| 2150 |
+
f 810//810 685//685 680//680
|
| 2151 |
+
f 918//918 662//662 801//801
|
| 2152 |
+
f 803//803 661//661 686//686
|
| 2153 |
+
f 917//917 666//666 660//660
|
| 2154 |
+
f 911//911 699//699 691//691
|
| 2155 |
+
f 912//912 694//694 914//914
|
| 2156 |
+
f 915//915 695//695 665//665
|
| 2157 |
+
f 708//708 704//704 902//902
|
| 2158 |
+
f 903//903 707//707 702//702
|
| 2159 |
+
f 906//906 701//701 913//913
|
robots/ur5/model/assets/forearm_2.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/forearm_3.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/pad.stl
ADDED
|
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
version https://git-lfs.github.com/spec/v1
|
| 2 |
+
oid sha256:4af1fa8d9bb285abecbf5dfc88e74cb30f059a7a074c2030dc35e9ee4316019d
|
| 3 |
+
size 15084
|
robots/ur5/model/assets/shoulder_0.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/shoulder_1.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/shoulder_2.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/silicone_pad.stl
ADDED
|
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
version https://git-lfs.github.com/spec/v1
|
| 2 |
+
oid sha256:ca20c0fa61e6d3ce7b04bed25360e048e31dfd88ace04187aa6d9e8f4ca3fd0f
|
| 3 |
+
size 15084
|
robots/ur5/model/assets/spring_link.stl
ADDED
|
@@ -0,0 +1,3 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
version https://git-lfs.github.com/spec/v1
|
| 2 |
+
oid sha256:4fb74a8a0d76c0e471cf19fd48bc676fd5b19123798e7a39eb6aa56869354283
|
| 3 |
+
size 84884
|
robots/ur5/model/assets/upperarm_0.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/upperarm_1.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/upperarm_2.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/upperarm_3.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/wrist1_0.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/wrist1_1.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/wrist1_2.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/wrist2_0.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/wrist2_1.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/wrist2_2.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/assets/wrist3.obj
ADDED
|
The diff for this file is too large to render.
See raw diff
|
|
|
robots/ur5/model/scene.xml
ADDED
|
@@ -0,0 +1,340 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<mujoco model="ur5e_with_gripper">
|
| 2 |
+
<compiler angle="radian" meshdir="assets" autolimits="true"/>
|
| 3 |
+
|
| 4 |
+
<option integrator="implicitfast" cone="elliptic" impratio="10"/>
|
| 5 |
+
|
| 6 |
+
<visual>
|
| 7 |
+
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/>
|
| 8 |
+
<rgba haze="0.15 0.25 0.35 1"/>
|
| 9 |
+
<global azimuth="120" elevation="-20"/>
|
| 10 |
+
</visual>
|
| 11 |
+
|
| 12 |
+
<asset>
|
| 13 |
+
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/>
|
| 14 |
+
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3"
|
| 15 |
+
markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
| 16 |
+
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
| 17 |
+
<material name="table" rgba="0.6 0.5 0.4 1" specular="0.3" shininess="0.3"/>
|
| 18 |
+
<material name="target_mat" rgba="0.2 0.8 0.2 0.5" specular="0.5" shininess="0.5"/>
|
| 19 |
+
|
| 20 |
+
<!-- UR5e materials -->
|
| 21 |
+
<material name="black" rgba="0.033 0.033 0.033 1" specular="0.5" shininess="0.25"/>
|
| 22 |
+
<material name="jointgray" rgba="0.278 0.278 0.278 1" specular="0.5" shininess="0.25"/>
|
| 23 |
+
<material name="linkgray" rgba="0.82 0.82 0.82 1" specular="0.5" shininess="0.25"/>
|
| 24 |
+
<material name="urblue" rgba="0.49 0.678 0.8 1" specular="0.5" shininess="0.25"/>
|
| 25 |
+
|
| 26 |
+
<!-- Gripper materials -->
|
| 27 |
+
<material name="metal" rgba="0.58 0.58 0.58 1"/>
|
| 28 |
+
<material name="silicone" rgba="0.1882 0.1882 0.1882 1"/>
|
| 29 |
+
<material name="gray" rgba="0.4627 0.4627 0.4627 1"/>
|
| 30 |
+
|
| 31 |
+
<!-- UR5e meshes -->
|
| 32 |
+
<mesh file="base_0.obj"/>
|
| 33 |
+
<mesh file="base_1.obj"/>
|
| 34 |
+
<mesh file="shoulder_0.obj"/>
|
| 35 |
+
<mesh file="shoulder_1.obj"/>
|
| 36 |
+
<mesh file="shoulder_2.obj"/>
|
| 37 |
+
<mesh file="upperarm_0.obj"/>
|
| 38 |
+
<mesh file="upperarm_1.obj"/>
|
| 39 |
+
<mesh file="upperarm_2.obj"/>
|
| 40 |
+
<mesh file="upperarm_3.obj"/>
|
| 41 |
+
<mesh file="forearm_0.obj"/>
|
| 42 |
+
<mesh file="forearm_1.obj"/>
|
| 43 |
+
<mesh file="forearm_2.obj"/>
|
| 44 |
+
<mesh file="forearm_3.obj"/>
|
| 45 |
+
<mesh file="wrist1_0.obj"/>
|
| 46 |
+
<mesh file="wrist1_1.obj"/>
|
| 47 |
+
<mesh file="wrist1_2.obj"/>
|
| 48 |
+
<mesh file="wrist2_0.obj"/>
|
| 49 |
+
<mesh file="wrist2_1.obj"/>
|
| 50 |
+
<mesh file="wrist2_2.obj"/>
|
| 51 |
+
<mesh file="wrist3.obj"/>
|
| 52 |
+
|
| 53 |
+
<!-- Gripper meshes -->
|
| 54 |
+
<mesh name="base_mount" file="base_mount.stl" scale="0.001 0.001 0.001"/>
|
| 55 |
+
<mesh name="base_g" file="base.stl" scale="0.001 0.001 0.001"/>
|
| 56 |
+
<mesh name="driver" file="driver.stl" scale="0.001 0.001 0.001"/>
|
| 57 |
+
<mesh name="coupler" file="coupler.stl" scale="0.001 0.001 0.001"/>
|
| 58 |
+
<mesh name="follower" file="follower.stl" scale="0.001 0.001 0.001"/>
|
| 59 |
+
<mesh name="pad" file="pad.stl" scale="0.001 0.001 0.001"/>
|
| 60 |
+
<mesh name="silicone_pad" file="silicone_pad.stl" scale="0.001 0.001 0.001"/>
|
| 61 |
+
<mesh name="spring_link" file="spring_link.stl" scale="0.001 0.001 0.001"/>
|
| 62 |
+
</asset>
|
| 63 |
+
|
| 64 |
+
<default>
|
| 65 |
+
<default class="ur5e">
|
| 66 |
+
<joint axis="0 1 0" range="-6.28319 6.28319" armature="0.1"/>
|
| 67 |
+
<general gaintype="fixed" biastype="affine" ctrlrange="-6.2831 6.2831" gainprm="2000" biasprm="0 -2000 -400" forcerange="-150 150"/>
|
| 68 |
+
<default class="size3">
|
| 69 |
+
<default class="size3_limited">
|
| 70 |
+
<joint range="-3.1415 3.1415"/>
|
| 71 |
+
<general ctrlrange="-3.1415 3.1415"/>
|
| 72 |
+
</default>
|
| 73 |
+
</default>
|
| 74 |
+
<default class="size1">
|
| 75 |
+
<general gainprm="500" biasprm="0 -500 -100" forcerange="-28 28"/>
|
| 76 |
+
</default>
|
| 77 |
+
<default class="visual">
|
| 78 |
+
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
|
| 79 |
+
</default>
|
| 80 |
+
<default class="collision">
|
| 81 |
+
<geom type="capsule" group="3"/>
|
| 82 |
+
<default class="eef_collision">
|
| 83 |
+
<geom type="cylinder"/>
|
| 84 |
+
</default>
|
| 85 |
+
</default>
|
| 86 |
+
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
|
| 87 |
+
</default>
|
| 88 |
+
|
| 89 |
+
<default class="gripper">
|
| 90 |
+
<general biastype="affine"/>
|
| 91 |
+
<joint axis="1 0 0"/>
|
| 92 |
+
<default class="driver_j">
|
| 93 |
+
<joint range="0 0.8" armature="0.005" damping="0.1" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
|
| 94 |
+
</default>
|
| 95 |
+
<default class="follower_j">
|
| 96 |
+
<joint range="-0.872664 0.872664" armature="0.001" pos="0 -0.018 0.0065" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
|
| 97 |
+
</default>
|
| 98 |
+
<default class="spring_link_j">
|
| 99 |
+
<joint range="-0.29670597283 0.8" armature="0.001" stiffness="0.05" springref="2.62" damping="0.00125"/>
|
| 100 |
+
</default>
|
| 101 |
+
<default class="coupler_j">
|
| 102 |
+
<joint range="-1.57 0" armature="0.001" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
|
| 103 |
+
</default>
|
| 104 |
+
<default class="visual_g">
|
| 105 |
+
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
|
| 106 |
+
</default>
|
| 107 |
+
<default class="collision_g">
|
| 108 |
+
<geom type="mesh" group="3"/>
|
| 109 |
+
<default class="pad_box1">
|
| 110 |
+
<geom mass="0" type="box" pos="0 -0.0026 0.028125" size="0.011 0.004 0.009375" friction="0.7"
|
| 111 |
+
solimp="0.95 0.99 0.001" solref="0.004 1" priority="1" rgba="0.55 0.55 0.55 1"/>
|
| 112 |
+
</default>
|
| 113 |
+
<default class="pad_box2">
|
| 114 |
+
<geom mass="0" type="box" pos="0 -0.0026 0.009375" size="0.011 0.004 0.009375" friction="0.6"
|
| 115 |
+
solimp="0.95 0.99 0.001" solref="0.004 1" priority="1" rgba="0.45 0.45 0.45 1"/>
|
| 116 |
+
</default>
|
| 117 |
+
</default>
|
| 118 |
+
</default>
|
| 119 |
+
</default>
|
| 120 |
+
|
| 121 |
+
<worldbody>
|
| 122 |
+
<light pos="0 0 3.5" dir="0 0 -1" directional="true"/>
|
| 123 |
+
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
| 124 |
+
|
| 125 |
+
<!-- Table -->
|
| 126 |
+
<body name="table" pos="0 0 0">
|
| 127 |
+
<geom name="table_top" type="box" pos="0.5 0 0.4" size="0.4 0.6 0.02" material="table"/>
|
| 128 |
+
<geom name="table_leg1" type="box" pos="0.2 0.4 0.2" size="0.03 0.03 0.2" material="table"/>
|
| 129 |
+
<geom name="table_leg2" type="box" pos="0.2 -0.4 0.2" size="0.03 0.03 0.2" material="table"/>
|
| 130 |
+
<geom name="table_leg3" type="box" pos="0.8 0.4 0.2" size="0.03 0.03 0.2" material="table"/>
|
| 131 |
+
<geom name="table_leg4" type="box" pos="0.8 -0.4 0.2" size="0.03 0.03 0.2" material="table"/>
|
| 132 |
+
</body>
|
| 133 |
+
|
| 134 |
+
<!-- Target visualization sphere (for IK target) -->
|
| 135 |
+
<body name="target" pos="0.4 0.0 0.6" mocap="true">
|
| 136 |
+
<geom name="target_vis" type="sphere" size="0.03" material="target_mat" contype="0" conaffinity="0"/>
|
| 137 |
+
</body>
|
| 138 |
+
|
| 139 |
+
<!-- UR5e robot mounted on table edge -->
|
| 140 |
+
<body name="base" pos="0 0 0.42" quat="0 0 0 -1" childclass="ur5e">
|
| 141 |
+
<inertial mass="4.0" pos="0 0 0" diaginertia="0.00443333156 0.00443333156 0.0072"/>
|
| 142 |
+
<geom mesh="base_0" material="black" class="visual"/>
|
| 143 |
+
<geom mesh="base_1" material="jointgray" class="visual"/>
|
| 144 |
+
<body name="shoulder_link" pos="0 0 0.163">
|
| 145 |
+
<inertial mass="3.7" pos="0 0 0" diaginertia="0.0102675 0.0102675 0.00666"/>
|
| 146 |
+
<joint name="shoulder_pan_joint" class="size3" axis="0 0 1"/>
|
| 147 |
+
<geom mesh="shoulder_0" material="urblue" class="visual"/>
|
| 148 |
+
<geom mesh="shoulder_1" material="black" class="visual"/>
|
| 149 |
+
<geom mesh="shoulder_2" material="jointgray" class="visual"/>
|
| 150 |
+
<geom class="collision" size="0.06 0.06" pos="0 0 -0.04"/>
|
| 151 |
+
<body name="upper_arm_link" pos="0 0.138 0" quat="1 0 1 0">
|
| 152 |
+
<inertial mass="8.393" pos="0 0 0.2125" diaginertia="0.133886 0.133886 0.0151074"/>
|
| 153 |
+
<joint name="shoulder_lift_joint" class="size3"/>
|
| 154 |
+
<geom mesh="upperarm_0" material="linkgray" class="visual"/>
|
| 155 |
+
<geom mesh="upperarm_1" material="black" class="visual"/>
|
| 156 |
+
<geom mesh="upperarm_2" material="jointgray" class="visual"/>
|
| 157 |
+
<geom mesh="upperarm_3" material="urblue" class="visual"/>
|
| 158 |
+
<geom class="collision" pos="0 -0.04 0" quat="1 1 0 0" size="0.06 0.06"/>
|
| 159 |
+
<geom class="collision" size="0.05 0.2" pos="0 0 0.2"/>
|
| 160 |
+
<body name="forearm_link" pos="0 -0.131 0.425">
|
| 161 |
+
<inertial mass="2.275" pos="0 0 0.196" diaginertia="0.0311796 0.0311796 0.004095"/>
|
| 162 |
+
<joint name="elbow_joint" class="size3_limited"/>
|
| 163 |
+
<geom mesh="forearm_0" material="urblue" class="visual"/>
|
| 164 |
+
<geom mesh="forearm_1" material="linkgray" class="visual"/>
|
| 165 |
+
<geom mesh="forearm_2" material="black" class="visual"/>
|
| 166 |
+
<geom mesh="forearm_3" material="jointgray" class="visual"/>
|
| 167 |
+
<geom class="collision" pos="0 0.08 0" quat="1 1 0 0" size="0.055 0.06"/>
|
| 168 |
+
<geom class="collision" size="0.038 0.19" pos="0 0 0.2"/>
|
| 169 |
+
<body name="wrist_1_link" pos="0 0 0.392" quat="1 0 1 0">
|
| 170 |
+
<inertial mass="1.219" pos="0 0.127 0" diaginertia="0.0025599 0.0025599 0.0021942"/>
|
| 171 |
+
<joint name="wrist_1_joint" class="size1"/>
|
| 172 |
+
<geom mesh="wrist1_0" material="black" class="visual"/>
|
| 173 |
+
<geom mesh="wrist1_1" material="urblue" class="visual"/>
|
| 174 |
+
<geom mesh="wrist1_2" material="jointgray" class="visual"/>
|
| 175 |
+
<geom class="collision" pos="0 0.05 0" quat="1 1 0 0" size="0.04 0.07"/>
|
| 176 |
+
<body name="wrist_2_link" pos="0 0.127 0">
|
| 177 |
+
<inertial mass="1.219" pos="0 0 0.1" diaginertia="0.0025599 0.0025599 0.0021942"/>
|
| 178 |
+
<joint name="wrist_2_joint" axis="0 0 1" class="size1"/>
|
| 179 |
+
<geom mesh="wrist2_0" material="black" class="visual"/>
|
| 180 |
+
<geom mesh="wrist2_1" material="urblue" class="visual"/>
|
| 181 |
+
<geom mesh="wrist2_2" material="jointgray" class="visual"/>
|
| 182 |
+
<geom class="collision" size="0.04 0.06" pos="0 0 0.04"/>
|
| 183 |
+
<geom class="collision" pos="0 0.02 0.1" quat="1 1 0 0" size="0.04 0.04"/>
|
| 184 |
+
<body name="wrist_3_link" pos="0 0 0.1">
|
| 185 |
+
<inertial mass="0.1889" pos="0 0.0771683 0" quat="1 0 0 1"
|
| 186 |
+
diaginertia="0.000132134 9.90863e-05 9.90863e-05"/>
|
| 187 |
+
<joint name="wrist_3_joint" class="size1"/>
|
| 188 |
+
<geom material="linkgray" mesh="wrist3" class="visual"/>
|
| 189 |
+
<geom class="eef_collision" pos="0 0.08 0" quat="1 1 0 0" size="0.04 0.02"/>
|
| 190 |
+
<site name="attachment_site" pos="0 0.1 0" quat="-1 1 0 0"/>
|
| 191 |
+
|
| 192 |
+
<!-- Gripper attached to wrist -->
|
| 193 |
+
<body name="gripper_base_mount" pos="0 0.1 0" quat="-1 1 0 0" childclass="gripper">
|
| 194 |
+
<body name="gripper_base_mount_inner" pos="0 0 0.007">
|
| 195 |
+
<geom class="visual_g" mesh="base_mount" material="black"/>
|
| 196 |
+
<geom class="collision_g" mesh="base_mount"/>
|
| 197 |
+
<body name="gripper_base" pos="0 0 0.0038" quat="1 0 0 -1">
|
| 198 |
+
<inertial mass="0.777441" pos="0 -2.70394e-05 0.0354675" quat="1 -0.00152849 0 0"
|
| 199 |
+
diaginertia="0.000260285 0.000225381 0.000152708"/>
|
| 200 |
+
<geom class="visual_g" mesh="base_g" material="black"/>
|
| 201 |
+
<geom class="collision_g" mesh="base_g"/>
|
| 202 |
+
<site name="pinch" pos="0 0 0.145" type="sphere" group="5" rgba="0.9 0.9 0.9 1" size="0.005"/>
|
| 203 |
+
<!-- End-effector site for IK -->
|
| 204 |
+
<site name="ee_site" pos="0 0 0.16" type="sphere" size="0.01" rgba="1 0 0 0.5"/>
|
| 205 |
+
|
| 206 |
+
<!-- Right-hand side 4-bar linkage -->
|
| 207 |
+
<body name="right_driver" pos="0 0.0306011 0.054904">
|
| 208 |
+
<inertial mass="0.00899563" pos="2.96931e-12 0.0177547 0.00107314" quat="0.681301 0.732003 0 0"
|
| 209 |
+
diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/>
|
| 210 |
+
<joint name="right_driver_joint" class="driver_j"/>
|
| 211 |
+
<geom class="visual_g" mesh="driver" material="gray"/>
|
| 212 |
+
<geom class="collision_g" mesh="driver"/>
|
| 213 |
+
<body name="right_coupler" pos="0 0.0315 -0.0041">
|
| 214 |
+
<inertial mass="0.0140974" pos="0 0.00301209 0.0232175" quat="0.705636 -0.0455904 0.0455904 0.705636"
|
| 215 |
+
diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/>
|
| 216 |
+
<joint name="right_coupler_joint" class="coupler_j"/>
|
| 217 |
+
<geom class="visual_g" mesh="coupler" material="black"/>
|
| 218 |
+
<geom class="collision_g" mesh="coupler"/>
|
| 219 |
+
</body>
|
| 220 |
+
</body>
|
| 221 |
+
<body name="right_spring_link" pos="0 0.0132 0.0609">
|
| 222 |
+
<inertial mass="0.0221642" pos="-8.65005e-09 0.0181624 0.0212658" quat="0.663403 -0.244737 0.244737 0.663403"
|
| 223 |
+
diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/>
|
| 224 |
+
<joint name="right_spring_link_joint" class="spring_link_j"/>
|
| 225 |
+
<geom class="visual_g" mesh="spring_link" material="black"/>
|
| 226 |
+
<geom class="collision_g" mesh="spring_link"/>
|
| 227 |
+
<body name="right_follower" pos="0 0.055 0.0375">
|
| 228 |
+
<inertial mass="0.0125222" pos="0 -0.011046 0.0124786" quat="1 0.1664 0 0"
|
| 229 |
+
diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/>
|
| 230 |
+
<joint name="right_follower_joint" class="follower_j"/>
|
| 231 |
+
<geom class="visual_g" mesh="follower" material="black"/>
|
| 232 |
+
<geom class="collision_g" mesh="follower"/>
|
| 233 |
+
<body name="right_pad" pos="0 -0.0189 0.01352">
|
| 234 |
+
<geom class="pad_box1" name="right_pad1"/>
|
| 235 |
+
<geom class="pad_box2" name="right_pad2"/>
|
| 236 |
+
<inertial mass="0.0035" pos="0 -0.0025 0.0185" quat="0.707107 0 0 0.707107"
|
| 237 |
+
diaginertia="4.73958e-07 3.64583e-07 1.23958e-07"/>
|
| 238 |
+
<geom class="visual_g" mesh="pad"/>
|
| 239 |
+
<body name="right_silicone_pad">
|
| 240 |
+
<geom class="visual_g" mesh="silicone_pad" material="black"/>
|
| 241 |
+
</body>
|
| 242 |
+
</body>
|
| 243 |
+
</body>
|
| 244 |
+
</body>
|
| 245 |
+
<!-- Left-hand side 4-bar linkage -->
|
| 246 |
+
<body name="left_driver" pos="0 -0.0306011 0.054904" quat="0 0 0 1">
|
| 247 |
+
<inertial mass="0.00899563" pos="0 0.0177547 0.00107314" quat="0.681301 0.732003 0 0"
|
| 248 |
+
diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/>
|
| 249 |
+
<joint name="left_driver_joint" class="driver_j"/>
|
| 250 |
+
<geom class="visual_g" mesh="driver" material="gray"/>
|
| 251 |
+
<geom class="collision_g" mesh="driver"/>
|
| 252 |
+
<body name="left_coupler" pos="0 0.0315 -0.0041">
|
| 253 |
+
<inertial mass="0.0140974" pos="0 0.00301209 0.0232175" quat="0.705636 -0.0455904 0.0455904 0.705636"
|
| 254 |
+
diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/>
|
| 255 |
+
<joint name="left_coupler_joint" class="coupler_j"/>
|
| 256 |
+
<geom class="visual_g" mesh="coupler" material="black"/>
|
| 257 |
+
<geom class="collision_g" mesh="coupler"/>
|
| 258 |
+
</body>
|
| 259 |
+
</body>
|
| 260 |
+
<body name="left_spring_link" pos="0 -0.0132 0.0609" quat="0 0 0 1">
|
| 261 |
+
<inertial mass="0.0221642" pos="-8.65005e-09 0.0181624 0.0212658" quat="0.663403 -0.244737 0.244737 0.663403"
|
| 262 |
+
diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/>
|
| 263 |
+
<joint name="left_spring_link_joint" class="spring_link_j"/>
|
| 264 |
+
<geom class="visual_g" mesh="spring_link" material="black"/>
|
| 265 |
+
<geom class="collision_g" mesh="spring_link"/>
|
| 266 |
+
<body name="left_follower" pos="0 0.055 0.0375">
|
| 267 |
+
<inertial mass="0.0125222" pos="0 -0.011046 0.0124786" quat="1 0.1664 0 0"
|
| 268 |
+
diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/>
|
| 269 |
+
<joint name="left_follower_joint" class="follower_j"/>
|
| 270 |
+
<geom class="visual_g" mesh="follower" material="black"/>
|
| 271 |
+
<geom class="collision_g" mesh="follower"/>
|
| 272 |
+
<body name="left_pad" pos="0 -0.0189 0.01352">
|
| 273 |
+
<geom class="pad_box1" name="left_pad1"/>
|
| 274 |
+
<geom class="pad_box2" name="left_pad2"/>
|
| 275 |
+
<inertial mass="0.0035" pos="0 -0.0025 0.0185" quat="1 0 0 1"
|
| 276 |
+
diaginertia="4.73958e-07 3.64583e-07 1.23958e-07"/>
|
| 277 |
+
<geom class="visual_g" mesh="pad"/>
|
| 278 |
+
<body name="left_silicone_pad">
|
| 279 |
+
<geom class="visual_g" mesh="silicone_pad" material="black"/>
|
| 280 |
+
</body>
|
| 281 |
+
</body>
|
| 282 |
+
</body>
|
| 283 |
+
</body>
|
| 284 |
+
</body>
|
| 285 |
+
</body>
|
| 286 |
+
</body>
|
| 287 |
+
</body>
|
| 288 |
+
</body>
|
| 289 |
+
</body>
|
| 290 |
+
</body>
|
| 291 |
+
</body>
|
| 292 |
+
</body>
|
| 293 |
+
</body>
|
| 294 |
+
|
| 295 |
+
<!-- Optional: object to manipulate -->
|
| 296 |
+
<body name="box" pos="0.5 0.2 0.45">
|
| 297 |
+
<freejoint name="box_joint"/>
|
| 298 |
+
<geom name="box_geom" type="box" size="0.025 0.025 0.025" rgba="1 0.3 0.3 1" mass="0.1"/>
|
| 299 |
+
</body>
|
| 300 |
+
</worldbody>
|
| 301 |
+
|
| 302 |
+
<contact>
|
| 303 |
+
<exclude body1="gripper_base" body2="left_driver"/>
|
| 304 |
+
<exclude body1="gripper_base" body2="right_driver"/>
|
| 305 |
+
<exclude body1="gripper_base" body2="left_spring_link"/>
|
| 306 |
+
<exclude body1="gripper_base" body2="right_spring_link"/>
|
| 307 |
+
<exclude body1="right_coupler" body2="right_follower"/>
|
| 308 |
+
<exclude body1="left_coupler" body2="left_follower"/>
|
| 309 |
+
</contact>
|
| 310 |
+
|
| 311 |
+
<tendon>
|
| 312 |
+
<fixed name="split">
|
| 313 |
+
<joint joint="right_driver_joint" coef="0.5"/>
|
| 314 |
+
<joint joint="left_driver_joint" coef="0.5"/>
|
| 315 |
+
</fixed>
|
| 316 |
+
</tendon>
|
| 317 |
+
|
| 318 |
+
<equality>
|
| 319 |
+
<connect anchor="0 0 0" body1="right_follower" body2="right_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/>
|
| 320 |
+
<connect anchor="0 0 0" body1="left_follower" body2="left_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/>
|
| 321 |
+
<joint joint1="right_driver_joint" joint2="left_driver_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001" solref="0.005 1"/>
|
| 322 |
+
</equality>
|
| 323 |
+
|
| 324 |
+
<actuator>
|
| 325 |
+
<!-- UR5e joint actuators -->
|
| 326 |
+
<general class="size3" name="shoulder_pan" joint="shoulder_pan_joint"/>
|
| 327 |
+
<general class="size3" name="shoulder_lift" joint="shoulder_lift_joint"/>
|
| 328 |
+
<general class="size3_limited" name="elbow" joint="elbow_joint"/>
|
| 329 |
+
<general class="size1" name="wrist_1" joint="wrist_1_joint"/>
|
| 330 |
+
<general class="size1" name="wrist_2" joint="wrist_2_joint"/>
|
| 331 |
+
<general class="size1" name="wrist_3" joint="wrist_3_joint"/>
|
| 332 |
+
<!-- Gripper actuator -->
|
| 333 |
+
<general name="gripper" tendon="split" forcerange="-5 5" ctrlrange="0 255" gainprm="0.3137255 0 0" biasprm="0 -100 -10"/>
|
| 334 |
+
</actuator>
|
| 335 |
+
|
| 336 |
+
<keyframe>
|
| 337 |
+
<key name="home" qpos="-1.5708 -1.5708 1.5708 -1.5708 -1.5708 0 0 0 0 0 0 0 0 0 0.5 0.2 0.45 1 0 0 0"
|
| 338 |
+
ctrl="-1.5708 -1.5708 1.5708 -1.5708 -1.5708 0 128"/>
|
| 339 |
+
</keyframe>
|
| 340 |
+
</mujoco>
|
robots/ur5/ur5_env.py
ADDED
|
@@ -0,0 +1,302 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
"""Gymnasium environment for Universal Robots UR5e with Robotiq 2F-85 gripper."""
|
| 2 |
+
import gymnasium as gym
|
| 3 |
+
from gymnasium import spaces
|
| 4 |
+
import numpy as np
|
| 5 |
+
import mujoco
|
| 6 |
+
import os
|
| 7 |
+
import importlib.util
|
| 8 |
+
|
| 9 |
+
# Import IK controller
|
| 10 |
+
_ur5_dir = os.path.dirname(os.path.abspath(__file__))
|
| 11 |
+
_ik_path = os.path.join(_ur5_dir, "controllers", "ik_controller.py")
|
| 12 |
+
_spec = importlib.util.spec_from_file_location("ur5_ik", _ik_path)
|
| 13 |
+
_ik_module = importlib.util.module_from_spec(_spec)
|
| 14 |
+
_spec.loader.exec_module(_ik_module)
|
| 15 |
+
IKController = _ik_module.IKController
|
| 16 |
+
|
| 17 |
+
|
| 18 |
+
class UR5Env(gym.Env):
|
| 19 |
+
"""
|
| 20 |
+
Gymnasium environment for Universal Robots UR5e with Robotiq 2F-85 gripper.
|
| 21 |
+
UR5e has 6 actuated joints, gripper has 1 actuator controlling both fingers.
|
| 22 |
+
"""
|
| 23 |
+
metadata = {"render_modes": ["human", "rgb_array"], "render_fps": 30}
|
| 24 |
+
|
| 25 |
+
# UR5e joint names (6 joints)
|
| 26 |
+
JOINT_NAMES = [
|
| 27 |
+
"shoulder_pan_joint",
|
| 28 |
+
"shoulder_lift_joint",
|
| 29 |
+
"elbow_joint",
|
| 30 |
+
"wrist_1_joint",
|
| 31 |
+
"wrist_2_joint",
|
| 32 |
+
"wrist_3_joint",
|
| 33 |
+
]
|
| 34 |
+
|
| 35 |
+
# Home position (arm pointing up and forward)
|
| 36 |
+
DEFAULT_HOME_POSE = np.array([
|
| 37 |
+
-1.5708, # shoulder_pan
|
| 38 |
+
-1.5708, # shoulder_lift
|
| 39 |
+
1.5708, # elbow
|
| 40 |
+
-1.5708, # wrist_1
|
| 41 |
+
-1.5708, # wrist_2
|
| 42 |
+
0.0, # wrist_3
|
| 43 |
+
], dtype=np.float32)
|
| 44 |
+
|
| 45 |
+
def __init__(self, render_mode=None, width=1280, height=720):
|
| 46 |
+
"""Initialize UR5e environment.
|
| 47 |
+
|
| 48 |
+
Args:
|
| 49 |
+
render_mode: 'human' or 'rgb_array'
|
| 50 |
+
width: Render width
|
| 51 |
+
height: Render height
|
| 52 |
+
"""
|
| 53 |
+
super().__init__()
|
| 54 |
+
|
| 55 |
+
# Load model
|
| 56 |
+
ur5_dir = os.path.dirname(os.path.abspath(__file__))
|
| 57 |
+
model_path = os.path.join(ur5_dir, "model", "scene.xml")
|
| 58 |
+
self.model = mujoco.MjModel.from_xml_path(model_path)
|
| 59 |
+
|
| 60 |
+
# Override framebuffer size
|
| 61 |
+
self.model.vis.global_.offwidth = width
|
| 62 |
+
self.model.vis.global_.offheight = height
|
| 63 |
+
|
| 64 |
+
self.data = mujoco.MjData(self.model)
|
| 65 |
+
|
| 66 |
+
# Number of actuators: 6 arm joints + 1 gripper
|
| 67 |
+
self.num_arm_actuators = 6
|
| 68 |
+
self.num_actuators = self.model.nu # 7 total
|
| 69 |
+
|
| 70 |
+
# Find site IDs
|
| 71 |
+
self.ee_site_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_SITE, "ee_site")
|
| 72 |
+
self.target_body_id = mujoco.mj_name2id(self.model, mujoco.mjtObj.mjOBJ_BODY, "target")
|
| 73 |
+
|
| 74 |
+
# Action space: 6 joint positions + 1 gripper (0-255)
|
| 75 |
+
self.action_space = spaces.Box(
|
| 76 |
+
low=np.array([-6.28, -6.28, -3.14, -6.28, -6.28, -6.28, 0], dtype=np.float32),
|
| 77 |
+
high=np.array([6.28, 6.28, 3.14, 6.28, 6.28, 6.28, 255], dtype=np.float32),
|
| 78 |
+
dtype=np.float32
|
| 79 |
+
)
|
| 80 |
+
|
| 81 |
+
# Observation space:
|
| 82 |
+
# - Joint positions (6)
|
| 83 |
+
# - Joint velocities (6)
|
| 84 |
+
# - End-effector position (3)
|
| 85 |
+
# - End-effector orientation (4, quaternion)
|
| 86 |
+
# - Gripper state (1)
|
| 87 |
+
# - Target position (3)
|
| 88 |
+
# Total: 6 + 6 + 3 + 4 + 1 + 3 = 23
|
| 89 |
+
obs_dim = 23
|
| 90 |
+
self.observation_space = spaces.Box(
|
| 91 |
+
low=-np.inf, high=np.inf,
|
| 92 |
+
shape=(obs_dim,),
|
| 93 |
+
dtype=np.float32
|
| 94 |
+
)
|
| 95 |
+
|
| 96 |
+
self.render_mode = render_mode
|
| 97 |
+
self.width = width
|
| 98 |
+
self.height = height
|
| 99 |
+
self.renderer = None
|
| 100 |
+
|
| 101 |
+
self.steps = 0
|
| 102 |
+
self.max_steps = 1000
|
| 103 |
+
|
| 104 |
+
# IK controller for end-effector control
|
| 105 |
+
self.controller = IKController(
|
| 106 |
+
model=self.model,
|
| 107 |
+
data=self.data,
|
| 108 |
+
ee_site_name="ee_site",
|
| 109 |
+
arm_joint_names=self.JOINT_NAMES
|
| 110 |
+
)
|
| 111 |
+
|
| 112 |
+
# Target position for IK
|
| 113 |
+
self._target_pos = np.array([0.4, 0.0, 0.6], dtype=np.float32)
|
| 114 |
+
# Gripper target (0=closed, 255=open)
|
| 115 |
+
self._gripper_target = 128.0
|
| 116 |
+
|
| 117 |
+
# Control mode: 'ik' (end-effector target) or 'joint' (direct joint positions)
|
| 118 |
+
self._control_mode = 'ik'
|
| 119 |
+
# Direct joint targets (used when control_mode is 'joint')
|
| 120 |
+
self._joint_targets = self.DEFAULT_HOME_POSE.copy()
|
| 121 |
+
|
| 122 |
+
def set_target(self, x: float, y: float, z: float):
|
| 123 |
+
"""Set target position for IK controller."""
|
| 124 |
+
self._target_pos = np.array([x, y, z], dtype=np.float32)
|
| 125 |
+
# Update mocap body position for visualization
|
| 126 |
+
self.data.mocap_pos[0] = self._target_pos
|
| 127 |
+
|
| 128 |
+
def get_target(self):
|
| 129 |
+
"""Get current target position."""
|
| 130 |
+
return self._target_pos.copy()
|
| 131 |
+
|
| 132 |
+
def set_gripper(self, value: float):
|
| 133 |
+
"""Set gripper target (0=closed, 255=open)."""
|
| 134 |
+
self._gripper_target = np.clip(value, 0, 255)
|
| 135 |
+
|
| 136 |
+
def get_gripper(self):
|
| 137 |
+
"""Get gripper target."""
|
| 138 |
+
return self._gripper_target
|
| 139 |
+
|
| 140 |
+
def set_control_mode(self, mode: str):
|
| 141 |
+
"""Set control mode: 'ik' or 'joint'."""
|
| 142 |
+
if mode in ('ik', 'joint'):
|
| 143 |
+
self._control_mode = mode
|
| 144 |
+
|
| 145 |
+
def get_control_mode(self):
|
| 146 |
+
"""Get current control mode."""
|
| 147 |
+
return self._control_mode
|
| 148 |
+
|
| 149 |
+
def set_joint_positions(self, positions):
|
| 150 |
+
"""Set target joint positions directly (bypasses IK).
|
| 151 |
+
|
| 152 |
+
Args:
|
| 153 |
+
positions: Array of 6 joint angles in radians
|
| 154 |
+
"""
|
| 155 |
+
positions = np.array(positions, dtype=np.float32)
|
| 156 |
+
# Clamp to joint limits
|
| 157 |
+
positions = np.clip(positions, self.action_space.low[:6], self.action_space.high[:6])
|
| 158 |
+
self._joint_targets = positions
|
| 159 |
+
|
| 160 |
+
def get_joint_positions(self):
|
| 161 |
+
"""Get current joint positions."""
|
| 162 |
+
return self.data.qpos[:6].copy()
|
| 163 |
+
|
| 164 |
+
def get_joint_targets(self):
|
| 165 |
+
"""Get current joint targets."""
|
| 166 |
+
return self._joint_targets.copy()
|
| 167 |
+
|
| 168 |
+
def get_end_effector_pos(self):
|
| 169 |
+
"""Get current end-effector position."""
|
| 170 |
+
return self.data.site_xpos[self.ee_site_id].copy()
|
| 171 |
+
|
| 172 |
+
def get_end_effector_quat(self):
|
| 173 |
+
"""Get current end-effector orientation as quaternion."""
|
| 174 |
+
xmat = self.data.site_xmat[self.ee_site_id].reshape(3, 3)
|
| 175 |
+
return self._mat_to_quat(xmat)
|
| 176 |
+
|
| 177 |
+
def _mat_to_quat(self, mat):
|
| 178 |
+
"""Convert rotation matrix to quaternion."""
|
| 179 |
+
quat = np.zeros(4)
|
| 180 |
+
mujoco.mju_mat2Quat(quat, mat.flatten())
|
| 181 |
+
return quat
|
| 182 |
+
|
| 183 |
+
def _get_obs(self):
|
| 184 |
+
"""Get observation from simulation state."""
|
| 185 |
+
# Joint positions (6 arm joints)
|
| 186 |
+
joint_pos = self.data.qpos[:6].copy()
|
| 187 |
+
|
| 188 |
+
# Joint velocities
|
| 189 |
+
joint_vel = self.data.qvel[:6].copy()
|
| 190 |
+
|
| 191 |
+
# End-effector position
|
| 192 |
+
ee_pos = self.get_end_effector_pos()
|
| 193 |
+
|
| 194 |
+
# End-effector orientation
|
| 195 |
+
ee_quat = self.get_end_effector_quat()
|
| 196 |
+
|
| 197 |
+
# Gripper state (read from actuator ctrl, normalized)
|
| 198 |
+
gripper_state = np.array([self.data.ctrl[6] / 255.0])
|
| 199 |
+
|
| 200 |
+
# Target position
|
| 201 |
+
target = self._target_pos.copy()
|
| 202 |
+
|
| 203 |
+
return np.concatenate([
|
| 204 |
+
joint_pos, joint_vel, ee_pos, ee_quat, gripper_state, target
|
| 205 |
+
]).astype(np.float32)
|
| 206 |
+
|
| 207 |
+
def set_command(self, vx: float = 0.0, vy: float = 0.0, vyaw: float = 0.0):
|
| 208 |
+
"""Compatibility method - for arm robots, this does nothing.
|
| 209 |
+
Use set_target() instead."""
|
| 210 |
+
pass
|
| 211 |
+
|
| 212 |
+
def get_command(self):
|
| 213 |
+
"""Compatibility method - returns zeros for arm robots."""
|
| 214 |
+
return np.array([0.0, 0.0, 0.0], dtype=np.float32)
|
| 215 |
+
|
| 216 |
+
def reset(self, seed=None, options=None):
|
| 217 |
+
super().reset(seed=seed)
|
| 218 |
+
|
| 219 |
+
mujoco.mj_resetData(self.model, self.data)
|
| 220 |
+
|
| 221 |
+
# Set to home pose
|
| 222 |
+
self.data.qpos[:6] = self.DEFAULT_HOME_POSE.copy()
|
| 223 |
+
self.data.ctrl[:6] = self.DEFAULT_HOME_POSE.copy()
|
| 224 |
+
self.data.ctrl[6] = 128 # Gripper half open
|
| 225 |
+
|
| 226 |
+
# Reset box position
|
| 227 |
+
box_qpos_start = 6 + 8 # 6 arm joints + 8 gripper joints
|
| 228 |
+
self.data.qpos[box_qpos_start:box_qpos_start+3] = [0.5, 0.2, 0.45]
|
| 229 |
+
self.data.qpos[box_qpos_start+3:box_qpos_start+7] = [1, 0, 0, 0]
|
| 230 |
+
|
| 231 |
+
# Reset target
|
| 232 |
+
self._target_pos = np.array([0.4, 0.0, 0.6], dtype=np.float32)
|
| 233 |
+
self.data.mocap_pos[0] = self._target_pos
|
| 234 |
+
self._gripper_target = 128.0
|
| 235 |
+
|
| 236 |
+
mujoco.mj_forward(self.model, self.data)
|
| 237 |
+
|
| 238 |
+
self.steps = 0
|
| 239 |
+
|
| 240 |
+
observation = self._get_obs()
|
| 241 |
+
return observation, {}
|
| 242 |
+
|
| 243 |
+
def step(self, action):
|
| 244 |
+
"""Step with explicit action (for RL training)."""
|
| 245 |
+
# Apply action to actuators
|
| 246 |
+
self.data.ctrl[:] = action
|
| 247 |
+
|
| 248 |
+
# Step simulation
|
| 249 |
+
mujoco.mj_step(self.model, self.data)
|
| 250 |
+
self.steps += 1
|
| 251 |
+
|
| 252 |
+
observation = self._get_obs()
|
| 253 |
+
|
| 254 |
+
# Reward: distance to target
|
| 255 |
+
ee_pos = self.get_end_effector_pos()
|
| 256 |
+
dist = np.linalg.norm(ee_pos - self._target_pos)
|
| 257 |
+
reward = -dist
|
| 258 |
+
|
| 259 |
+
terminated = False
|
| 260 |
+
truncated = self.steps >= self.max_steps
|
| 261 |
+
|
| 262 |
+
info = {
|
| 263 |
+
"ee_pos": ee_pos,
|
| 264 |
+
"target_pos": self._target_pos,
|
| 265 |
+
"distance": dist,
|
| 266 |
+
}
|
| 267 |
+
|
| 268 |
+
return observation, reward, terminated, truncated, info
|
| 269 |
+
|
| 270 |
+
def step_with_controller(self, dt: float = 0.002):
|
| 271 |
+
"""Step using controller (IK or direct joint control)."""
|
| 272 |
+
if self._control_mode == 'ik':
|
| 273 |
+
# Compute IK to reach target position
|
| 274 |
+
joint_targets = self.controller.compute_ik(self._target_pos)
|
| 275 |
+
else:
|
| 276 |
+
# Use direct joint targets
|
| 277 |
+
joint_targets = self._joint_targets
|
| 278 |
+
|
| 279 |
+
# Apply joint targets
|
| 280 |
+
self.data.ctrl[:6] = joint_targets
|
| 281 |
+
|
| 282 |
+
# Apply gripper target
|
| 283 |
+
self.data.ctrl[6] = self._gripper_target
|
| 284 |
+
|
| 285 |
+
# Step simulation
|
| 286 |
+
mujoco.mj_step(self.model, self.data)
|
| 287 |
+
self.steps += 1
|
| 288 |
+
|
| 289 |
+
return self._get_obs()
|
| 290 |
+
|
| 291 |
+
def render(self):
|
| 292 |
+
if self.render_mode == "rgb_array":
|
| 293 |
+
if self.renderer is None:
|
| 294 |
+
self.renderer = mujoco.Renderer(self.model, height=self.height, width=self.width)
|
| 295 |
+
self.renderer.update_scene(self.data)
|
| 296 |
+
return self.renderer.render()
|
| 297 |
+
return None
|
| 298 |
+
|
| 299 |
+
def close(self):
|
| 300 |
+
if self.renderer:
|
| 301 |
+
self.renderer.close()
|
| 302 |
+
self.renderer = None
|