├── LICENSE
├── README.md
├── controllers
├── mavic2proController
│ ├── __pycache__
│ │ └── mavic2proHelper.cpython-37.pyc
│ ├── mavic2proController.py
│ ├── mavic2proHelper.py
│ └── mavic2proHelper.pyc
├── params.csv
└── pioneerController
│ ├── __pycache__
│ └── roverHelper.cpython-37.pyc
│ ├── pioneerController.py
│ └── roverHelper.py
├── docs
└── doc_image.jpeg
├── pathCSV
├── rover_waypoint_generator.py
└── waypoints.csv
├── protos
├── .CircleArena.cache
├── .Floor.cache
├── .Pioneer3DistanceSensor.cache
├── .Pioneer3Gripper.cache
├── .Pioneer3at.cache
├── .Pioneer3dx.cache
├── .RectangleArena.cache
├── .SandyGround.cache
├── .UnevenTerrain.cache
├── CircleArena.proto
├── Floor.proto
├── Pioneer3DistanceSensor.proto
├── Pioneer3Gripper.proto
├── Pioneer3at.proto
├── Pioneer3dx.proto
├── RectangleArena.proto
├── SandyGround.proto
├── UnevenTerrain.proto
├── icons
│ ├── CircleArena.png
│ ├── Floor.png
│ ├── Pioneer3DistanceSensor.png
│ ├── Pioneer3Gripper.png
│ ├── Pioneer3at.png
│ ├── Pioneer3dx.png
│ ├── RectangleArena.png
│ └── UnevenTerrain.png
└── textures
│ ├── Aruco.png
│ ├── body_3at_base_color.jpg
│ ├── body_3at_normal.jpg
│ ├── body_3at_occlusion.jpg
│ ├── body_3at_roughness.jpg
│ ├── body_3dx_base_color.jpg
│ ├── body_3dx_metalness.jpg
│ ├── body_3dx_normal.jpg
│ ├── body_3dx_occlusion.jpg
│ ├── body_3dx_roughness.jpg
│ ├── caster_wheel.jpg
│ ├── caster_wheel_base_color.jpg
│ ├── caster_wheel_normal.jpg
│ ├── caster_wheel_occlusion.jpg
│ ├── caster_wheel_roughness.jpg
│ ├── cross_tire.jpg
│ ├── cross_tire_base_color.jpg
│ ├── cross_tire_normal.jpg
│ ├── cross_tire_occlusion.jpg
│ ├── honeycomb_base_color.jpg
│ ├── honeycomb_normal.jpg
│ ├── rover_circuit.jpg
│ ├── serial_plug.jpg
│ ├── smooth_rubber.jpg
│ ├── smooth_rubber_base_color.jpg
│ ├── smooth_rubber_normal.jpg
│ ├── smooth_rubber_occlusion.jpg
│ ├── smooth_rubber_roughness.jpg
│ ├── top_3at_base_color.jpg
│ ├── top_3at_base_color_copy.jpg
│ ├── top_3dx_base_color.jpg
│ └── top_3dx_normal.jpg
└── worlds
├── .ObjectTracking.wbproj
├── .empty.wbproj
└── ObjectTracking.wbt
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2019 Prasad N R
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # Webots-Quadcopter-Python-SITL
2 |
3 | _Note: This repository fundamentally uses Webots to simulate robots. I found a critical bug in Webots. Camera flickers and rover gets stuck repeatedly. I tried to find a workaround. Link: https://github.com/cyberbotics/webots/issues/1081 However, in Webots, the coordinates are inherently flipped (y-axis along the floor). Given the problems of camera not working, rover getting stuck and flipped coordinates, I could understand that the controller cannot be made production-ready. So, I have archived this repository. However, the flight controller is built on sound math. So, it should work in any SITL or Python-based hardware._
4 |
5 | ## Background
6 |
7 | A couple of years ago, I had authored a paper on object tracking Quadcopter. (Link: https://www.academia.edu/40403950/Single_Horizontal_Camera-Based_Object_Tracking_Quadcopter_Using_StaGaus_Algorithm ) I had some difficulties with reproducible results (with physical drone as mentioned in the paper). However, back then, I ended up building a ROS and Gazebo based multi-type multi-vehicle SITL (Software In The Loop) simulator (as detailed in the paper). The setup was extensive and worked only with a specific version of Ubuntu (requiring `sudo` and root access).
8 |
9 | Also, few of the repositories have been archived now and I believe Erle Robotics has shut down completely and their github repositories are archived (which means that my ROS Gazebo SITL simulator may/may not be fully reproducible. At least, it won't be easy to reproduce my research to say the least).
10 |
11 | **_However, this simulator is a general purpose object tracking simulator and is not restricted to my research paper. My intention is to advance the standardisation of reinforcement learning, deep learning and the likes and make it simpler to achieve it._**
12 |
13 | ## Solution
14 |
15 | 1. Building a cross-platform compatible (main target OS being Windows, Linux and Mac OS) with pure Python implementation of controllers for multi-type, multi-vehicle SITL simulator. As I could not find anything like this yet for object tracking in Webots, I started out with Mavic 2 Pro Quadcopter and Pioneer 3DX rover.
16 |
17 | 2. I also wrote pure Python SITL Flight Controller (for waypoint navigation) as I could not find pure general purpose quadcopter controller in Python for SITL. It can also be used in hardware (and it is general purpose code, so, it will work with all hardwares that can run Python interpreter).
18 |
19 |
20 |
21 |
22 |
23 | ## Installation instructions
24 |
25 | 1. Install Webots (according to your OS).
26 | Link: https://cyberbotics.com/download
27 |
28 | 2. Install Python (according to your OS).
29 | Note: Any of the versions of Python supported by Webots is needed.
30 | Link: https://cyberbotics.com/doc/guide/using-python
31 |
32 | 3. Install libraries needed to run this simulation.
33 | a. `pip install simple-pid` Source: https://github.com/m-lundberg/simple-pid
34 | b. `pip install numpy`
35 | c. Install Python OpenCV.
36 | - `pip install opencv-contrib-python` (Preferred. However, this installs opencv-contrib which may contain patented algorithms. Unofficial community whl)
37 | - `pip install opencv-python` (Unofficial community whl)
38 | - Downloading source code from https://opencv.org and compiling (or checking if cv2.py or something like python2_cv.py and python3_cv.py files are present after downloading OpenCV exe executables (for Windows users only)). This method requires compilation and is not recommended unless performance is needed in simulations and it takes some time to install.
39 | - Ubuntu and linux users may be able to install OpenCV via system package managers like `apt`, `aptitude` etc.
40 |
41 | ## Running the simulator
42 |
43 | Just double click on (or run) _Webots-Quadcopter-Python-SITL/blob/master/worlds/ObjectTracking.wbt_
44 |
45 | ## FAQs:
46 |
47 | [What is the intuition of the math of the aerodynamics?](https://github.com/PrasadNR/Webots-Quadcopter-Python-SITL/issues/3)
48 |
49 | [Will there be other "cross-platform" simulator support/custom simulator support?](https://github.com/PrasadNR/Webots-Quadcopter-Python-SITL/issues/4)
50 |
--------------------------------------------------------------------------------
/controllers/mavic2proController/__pycache__/mavic2proHelper.cpython-37.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/controllers/mavic2proController/__pycache__/mavic2proHelper.cpython-37.pyc
--------------------------------------------------------------------------------
/controllers/mavic2proController/mavic2proController.py:
--------------------------------------------------------------------------------
1 | from controller import *
2 | import mavic2proHelper
3 | import cv2
4 | import numpy
5 | from simple_pid import PID
6 | import csv
7 | import struct
8 |
9 | params = dict()
10 | with open("../params.csv", "r") as f:
11 | lines = csv.reader(f)
12 | for line in lines:
13 | params[line[0]] = line[1]
14 |
15 | TIME_STEP = int(params["QUADCOPTER_TIME_STEP"])
16 | TAKEOFF_THRESHOLD_VELOCITY = int(params["TAKEOFF_THRESHOLD_VELOCITY"])
17 | M_PI = numpy.pi;
18 |
19 | target_altitude = float(params["target_altitude"])
20 |
21 | robot = Robot()
22 |
23 | [frontLeftMotor, frontRightMotor, backLeftMotor, backRightMotor] = mavic2proHelper.getMotorAll(robot)
24 |
25 | timestep = int(robot.getBasicTimeStep())
26 | mavic2proMotors = mavic2proHelper.getMotorAll(robot)
27 | mavic2proHelper.initialiseMotors(robot, 0)
28 | mavic2proHelper.motorsSpeed(robot, TAKEOFF_THRESHOLD_VELOCITY, TAKEOFF_THRESHOLD_VELOCITY, TAKEOFF_THRESHOLD_VELOCITY, TAKEOFF_THRESHOLD_VELOCITY)
29 |
30 | camera = Camera("camera")
31 | camera.enable(TIME_STEP)
32 | front_left_led = LED("front left led")
33 | front_right_led = LED("front right led")
34 | gps = GPS("gps")
35 | gps.enable(TIME_STEP)
36 | imu = InertialUnit("inertial unit")
37 | imu.enable(TIME_STEP)
38 | compass = Compass("compass")
39 | compass.enable(TIME_STEP)
40 | gyro = Gyro("gyro")
41 | gyro.enable(TIME_STEP)
42 | receiver = Receiver("receiver")
43 | receiver.enable(TIME_STEP)
44 |
45 | pitchPID = PID(float(params["pitch_Kp"]), float(params["pitch_Ki"]), float(params["pitch_Kd"]), setpoint=0.0)
46 | rollPID = PID(float(params["roll_Kp"]), float(params["roll_Ki"]), float(params["roll_Kd"]), setpoint=0.0)
47 | throttlePID = PID(float(params["throttle_Kp"]), float(params["throttle_Ki"]), float(params["throttle_Kd"]), setpoint=target_altitude)
48 | yawPID = PID(float(params["yaw_Kp"]), float(params["yaw_Ki"]), float(params["yaw_Kd"]), setpoint=float(params["yaw_setpoint"]))
49 |
50 | targetX, targetY, altitude_attained = 0.0, 0.0, False
51 |
52 | while (robot.step(timestep) != -1):
53 |
54 | led_state = int(robot.getTime()) % 2
55 | front_left_led.set(led_state)
56 | front_right_led.set(int(not(led_state)))
57 |
58 | roll = imu.getRollPitchYaw()[0] + M_PI / 2.0
59 | pitch = imu.getRollPitchYaw()[1]
60 | yaw = compass.getValues()[1]
61 | roll_acceleration = gyro.getValues()[0]
62 | pitch_acceleration = gyro.getValues()[1]
63 |
64 | xGPS = gps.getValues()[2]
65 | yGPS = gps.getValues()[0]
66 | zGPS = gps.getValues()[1]
67 |
68 | vertical_input = throttlePID(zGPS)
69 | yaw_input = yawPID(yaw)
70 |
71 | if zGPS > target_altitude * float(params["altitude_attainment_factor"]):
72 | altitude_attained = True
73 | #targetX = xRover
74 | #targetY = yRover
75 |
76 | if receiver.getQueueLength() > 0:
77 | message = receiver.getData().decode('utf-8')
78 | xRover, yRover = float(message.split(",")[0].strip()), float(message.split(",")[1].strip())
79 | receiver.nextPacket()
80 |
81 | if altitude_attained == False:
82 | targetX = -1.0
83 | targetY = -1.0
84 |
85 | rollPID.setpoint = -targetX
86 | pitchPID.setpoint = targetY
87 |
88 | roll_input = float(params["k_roll_p"]) * roll + roll_acceleration + rollPID(-xGPS)
89 | pitch_input = float(params["k_pitch_p"]) * pitch - pitch_acceleration + pitchPID(yGPS)
90 |
91 | #print(xGPS, yGPS)
92 |
93 | front_left_motor_input = float(params["k_vertical_thrust"]) + vertical_input - roll_input - pitch_input + yaw_input
94 | front_right_motor_input = float(params["k_vertical_thrust"]) + vertical_input + roll_input - pitch_input - yaw_input
95 | rear_left_motor_input = float(params["k_vertical_thrust"]) + vertical_input - roll_input + pitch_input - yaw_input
96 | rear_right_motor_input = float(params["k_vertical_thrust"]) + vertical_input + roll_input + pitch_input + yaw_input
97 |
98 | if not(numpy.isnan(front_left_motor_input)):
99 | mavic2proHelper.motorsSpeed(robot, front_left_motor_input, -front_right_motor_input, -rear_left_motor_input, rear_right_motor_input)
--------------------------------------------------------------------------------
/controllers/mavic2proController/mavic2proHelper.py:
--------------------------------------------------------------------------------
1 | def getMotorAll(robot):
2 | frontLeftMotor = robot.getMotor('front left propeller')
3 | frontRightMotor = robot.getMotor('front right propeller')
4 | backLeftMotor = robot.getMotor('rear left propeller')
5 | backRightMotor = robot.getMotor('rear right propeller')
6 | return [frontLeftMotor, frontRightMotor, backLeftMotor, backRightMotor]
7 |
8 | def motorsSpeed(robot, v1, v2, v3, v4):
9 | [frontLeftMotor, frontRightMotor, backLeftMotor, backRightMotor] = getMotorAll(robot)
10 | frontLeftMotor.setVelocity(v1)
11 | frontRightMotor.setVelocity(v2)
12 | backLeftMotor.setVelocity(v3)
13 | backRightMotor.setVelocity(v4)
14 | return
15 |
16 | def initialiseMotors(robot, MAX_PROPELLER_VELOCITY):
17 | [frontLeftMotor, frontRightMotor, backLeftMotor, backRightMotor] = getMotorAll(robot)
18 | frontLeftMotor.setPosition(float('inf'))
19 | frontRightMotor.setPosition(float('inf'))
20 | backLeftMotor.setPosition(float('inf'))
21 | backRightMotor.setPosition(float('inf'))
22 |
23 | motorsSpeed(robot, 0, 0, 0, 0)
24 | return
--------------------------------------------------------------------------------
/controllers/mavic2proController/mavic2proHelper.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/controllers/mavic2proController/mavic2proHelper.pyc
--------------------------------------------------------------------------------
/controllers/params.csv:
--------------------------------------------------------------------------------
1 | QUADCOPTER_TIME_STEP,8,ROVER_TIME_STEP,64
2 | TAKEOFF_THRESHOLD_VELOCITY,163,floor_width,70
3 | k_vertical_thrust,68.5,floor_height,42.4
4 | k_roll_p,5,waypoint_reached_tolerance,0.1
5 | k_pitch_p,10,,
6 | target_altitude,1.5,,
7 | pitch_Kp,2,,
8 | pitch_Ki,0,,
9 | pitch_Kd,2,,
10 | roll_Kp,2,,
11 | roll_Ki,0,,
12 | roll_Kd,3,,
13 | throttle_Kp,10,,
14 | throttle_Ki,0,,
15 | throttle_Kd,5,,
16 | yaw_Kp,2,,
17 | yaw_Ki,0,,
18 | yaw_Kd,3,,
19 | yaw_setpoint,0,,
20 | altitude_attainment_factor,0.8,,
21 |
--------------------------------------------------------------------------------
/controllers/pioneerController/__pycache__/roverHelper.cpython-37.pyc:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/controllers/pioneerController/__pycache__/roverHelper.cpython-37.pyc
--------------------------------------------------------------------------------
/controllers/pioneerController/pioneerController.py:
--------------------------------------------------------------------------------
1 | from controller import *
2 | import roverHelper
3 | import cv2
4 | import numpy
5 | import csv
6 |
7 | params = dict()
8 | with open("../params.csv", "r") as f:
9 | lines = csv.reader(f)
10 | for line in lines:
11 | params[line[2]] = line[3]
12 |
13 | TIME_STEP = int(params["ROVER_TIME_STEP"])
14 | robot = Robot()
15 | M_PI = numpy.pi
16 |
17 | [frontLeftMotor, frontRightMotor, backLeftMotor, backRightMotor] = roverHelper.getMotorAll(robot)
18 | MAX_WHEEL_VELOCITY = frontLeftMotor.getMaxVelocity()
19 |
20 | timestep = int(robot.getBasicTimeStep())
21 | roverHelper.initialiseMotors(robot, MAX_WHEEL_VELOCITY)
22 |
23 | gps = GPS("gps")
24 | gps.enable(TIME_STEP)
25 | emitter = Emitter("emitter")
26 | compass = Compass("compass")
27 | compass.enable(TIME_STEP)
28 |
29 | waypointCounter = 1
30 | waypoints = dict()
31 | image = cv2.imread("../../protos/textures/rover_circuit.jpg")
32 | numberOfWaypoints = 0
33 | with open("../../pathCSV/waypoints.csv", "r") as f:
34 | reader = csv.DictReader(f)
35 | for row in reader:
36 | coordinateX = numpy.interp(row["coordinateX"], [0, image.shape[1] - 1], [-float(params["floor_width"]) / 2, float(params["floor_width"]) / 2])
37 | coordinateY = numpy.interp(row["coordinateY"], [0, image.shape[0] - 1], [-float(params["floor_height"]) / 2, float(params["floor_height"]) / 2])
38 | waypoints[row["waypointID"]] = (coordinateX, coordinateY)
39 | numberOfWaypoints += 1
40 | #print(row["waypointID"], (coordinateX, coordinateY))
41 |
42 | teleoperaton = True #THIS VARIABLE IS ONLY FOR DEBUGGING PURPOSES AND USAGE OF THIS VARIABLE IN PRODUCTION IS HIGHLY DISCOURAGED. SET THIS TO False WHEN ROVER HAS TO BE AUTONOMOUS.
43 |
44 | if teleoperaton == True:
45 | keyboard = Keyboard();
46 | keyboard.enable(TIME_STEP);
47 |
48 | while (robot.step(timestep) != -1):
49 |
50 | if teleoperaton == True:
51 | key = keyboard.getKey();
52 | if key == keyboard.UP:
53 | roverHelper.movement.forward(robot, MAX_WHEEL_VELOCITY)
54 | if key == keyboard.LEFT:
55 | roverHelper.movement.left(robot, MAX_WHEEL_VELOCITY)
56 | if key == keyboard.DOWN:
57 | roverHelper.movement.backward(robot, MAX_WHEEL_VELOCITY)
58 | if key == keyboard.RIGHT:
59 | roverHelper.movement.right(robot, MAX_WHEEL_VELOCITY)
60 | if key == keyboard.END:
61 | roverHelper.movement.brake(robot, MAX_WHEEL_VELOCITY)
62 |
63 | gpsLocation = gps.getValues()
64 | compassValues = compass.getValues()
65 |
66 | xRover, yRover = gps.getValues()[2], gps.getValues()[0]
67 | emitter.send((str(xRover) + ", " + str(yRover)).encode('utf-8'))
68 |
69 | robotHeading = M_PI - numpy.arctan2(compassValues[0], compassValues[2])
70 | waypointX, waypointY = waypoints[str(waypointCounter)][0], waypoints[str(waypointCounter)][1]
71 | waypointHeading = numpy.arctan2(yRover - waypointY, xRover - waypointX) + M_PI / 2.0
72 | if waypointHeading < 0:
73 | waypointHeading = waypointHeading + 2 * M_PI
74 |
75 | steering = (robotHeading - waypointHeading) / M_PI
76 | steering = numpy.clip(steering, -1.0, 1.0)
77 |
78 | print(waypointHeading)
79 |
80 | if numpy.isnan(steering) == False:
81 | roverHelper.lineFollow(robot, MAX_WHEEL_VELOCITY, steering)
82 |
83 | roverWaypointDistance = numpy.sqrt((xRover - waypointX) * (xRover - waypointX) + (yRover - waypointY) * (yRover - waypointY))
84 |
85 | if roverWaypointDistance < float(params["waypoint_reached_tolerance"]):
86 | waypointCounter = (waypointCounter + 1) % numberOfWaypoints
--------------------------------------------------------------------------------
/controllers/pioneerController/roverHelper.py:
--------------------------------------------------------------------------------
1 | import numpy
2 |
3 | def getMotorAll(robot):
4 | frontLeftMotor = robot.getMotor('front left wheel')
5 | frontRightMotor = robot.getMotor('front right wheel')
6 | backLeftMotor = robot.getMotor('back left wheel')
7 | backRightMotor = robot.getMotor('back right wheel')
8 | return [frontLeftMotor, frontRightMotor, backLeftMotor, backRightMotor]
9 |
10 | def motorsSpeed(robot, v1, v2, v3, v4):
11 | [frontLeftMotor, frontRightMotor, backLeftMotor, backRightMotor] = getMotorAll(robot)
12 | frontLeftMotor.setVelocity(v1)
13 | frontRightMotor.setVelocity(v2)
14 | backLeftMotor.setVelocity(v3)
15 | backRightMotor.setVelocity(v4)
16 | return
17 |
18 | def lineFollow(robot, MAX_WHEEL_VELOCITY, k):
19 | [frontLeftMotor, frontRightMotor, backLeftMotor, backRightMotor] = getMotorAll(robot)
20 | vLeft = (1 - abs(k) + k) * MAX_WHEEL_VELOCITY
21 | vRight = (1 - abs(k) - k) * MAX_WHEEL_VELOCITY
22 | frontLeftMotor.setVelocity(vLeft)
23 | frontRightMotor.setVelocity(vRight)
24 | backLeftMotor.setVelocity(vLeft)
25 | backRightMotor.setVelocity(vRight)
26 | return
27 |
28 | class movement:
29 |
30 | def forward(robot, MAX_WHEEL_VELOCITY):
31 | motorsSpeed(robot, MAX_WHEEL_VELOCITY, MAX_WHEEL_VELOCITY, MAX_WHEEL_VELOCITY, MAX_WHEEL_VELOCITY)
32 | return
33 |
34 | def backward(robot, MAX_WHEEL_VELOCITY):
35 | motorsSpeed(robot, -MAX_WHEEL_VELOCITY, -MAX_WHEEL_VELOCITY, -MAX_WHEEL_VELOCITY, -MAX_WHEEL_VELOCITY)
36 | return
37 |
38 | def left(robot, MAX_WHEEL_VELOCITY):
39 | motorsSpeed(robot, -MAX_WHEEL_VELOCITY, MAX_WHEEL_VELOCITY, -MAX_WHEEL_VELOCITY, MAX_WHEEL_VELOCITY)
40 | return
41 |
42 | def right(robot, MAX_WHEEL_VELOCITY):
43 | motorsSpeed(robot, MAX_WHEEL_VELOCITY, -MAX_WHEEL_VELOCITY, MAX_WHEEL_VELOCITY, -MAX_WHEEL_VELOCITY)
44 | return
45 |
46 | def brake(robot, MAX_WHEEL_VELOCITY):
47 | motorsSpeed(robot, 0, 0, 0, 0)
48 | return
49 |
50 | def initialiseMotors(robot, MAX_WHEEL_VELOCITY):
51 | [frontLeftMotor, frontRightMotor, backLeftMotor, backRightMotor] = getMotorAll(robot)
52 | frontLeftMotor.setPosition(float('inf'))
53 | frontRightMotor.setPosition(float('inf'))
54 | backLeftMotor.setPosition(float('inf'))
55 | backRightMotor.setPosition(float('inf'))
56 |
57 | movement.brake(robot, MAX_WHEEL_VELOCITY)
58 | return
--------------------------------------------------------------------------------
/docs/doc_image.jpeg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/docs/doc_image.jpeg
--------------------------------------------------------------------------------
/pathCSV/rover_waypoint_generator.py:
--------------------------------------------------------------------------------
1 | import cv2
2 | import csv
3 |
4 | global clickCoordinates
5 | clickCoordinates = list()
6 |
7 | def click_point(event, x, y, flags, param):
8 | if event == cv2.EVENT_LBUTTONDOWN:
9 | clickCoordinates.append((x, y))
10 |
11 | image = cv2.imread("../protos/textures/rover_circuit.jpg")
12 | cv2.namedWindow("image")
13 | cv2.setMouseCallback("image", click_point)
14 |
15 | while True:
16 | cv2.imshow("image", image)
17 | key = cv2.waitKey(1)
18 | if key == ord(" "):
19 | break
20 |
21 | with open('waypoints.csv', 'w', newline='') as f:
22 | writer = csv.writer(f)
23 | writer.writerow(["waypointID", "coordinateX", "coordinateY"])
24 | for coordinateID, eachClickCoordinatePair in enumerate(clickCoordinates):
25 | writer.writerow([coordinateID, eachClickCoordinatePair[0], eachClickCoordinatePair[1]])
--------------------------------------------------------------------------------
/pathCSV/waypoints.csv:
--------------------------------------------------------------------------------
1 | waypointID,coordinateX,coordinateY
2 | 0,482,225
3 | 1,452,229
4 | 2,410,229
5 | 3,319,200
6 | 4,259,190
7 | 5,222,203
8 | 6,217,220
9 | 7,263,280
10 | 8,278,306
11 | 9,262,323
12 | 10,147,388
13 | 11,146,412
14 | 12,171,420
15 | 13,215,412
16 | 14,435,415
17 | 15,595,418
18 | 16,718,400
19 | 17,854,399
20 | 18,892,374
21 | 19,902,321
22 | 20,887,254
23 | 21,864,245
24 | 22,839,253
25 | 23,780,296
26 | 24,733,324
27 | 25,645,324
28 | 26,614,295
29 | 27,604,236
30 | 28,773,84
31 | 29,771,64
32 | 30,755,57
33 | 31,732,64
34 | 32,677,108
35 | 33,638,113
36 | 34,608,135
37 | 35,580,146
38 | 36,539,196
39 | 37,509,218
40 |
--------------------------------------------------------------------------------
/protos/.CircleArena.cache:
--------------------------------------------------------------------------------
1 | Webots Proto Cache File version 1.4
2 | protoFileHash: b34898ba565301099b90e689ceaa13b9
3 | containsDevices: 0
4 | baseType: Solid
5 | slotType:
6 | parameters: translation,rotation,name,radius,contactMaterial,floorAppearance,floorTileSize,wallThickness,wallHeight,wallAppearance,subdivision,floorTextureUrl,wallTextureUrl,wallTileSize
7 | tags: static
8 | license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
9 | licenseUrl: https://cyberbotics.com/webots_assets_license
10 | documentationUrl:
11 | info: A\sconfigurable\scircle\sarena\scomposed\sof\sfloor\ssurrounded\sby\swall.\n
12 |
--------------------------------------------------------------------------------
/protos/.Floor.cache:
--------------------------------------------------------------------------------
1 | Webots Proto Cache File version 1.4
2 | protoFileHash: 4057c5bb99ab9330c7854f70f35ce788
3 | containsDevices: 0
4 | baseType: Solid
5 | slotType:
6 | parameters: translation,rotation,name,contactMaterial,size,tileSize,appearance,texture
7 | tags: static
8 | license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
9 | licenseUrl: https://cyberbotics.com/webots_assets_license
10 | documentationUrl:
11 | info: Configurable\sstandard\sflat\sfloor.\n
12 |
--------------------------------------------------------------------------------
/protos/.Pioneer3DistanceSensor.cache:
--------------------------------------------------------------------------------
1 | Webots Proto Cache File version 1.4
2 | protoFileHash: c50dbf1d22b0c708f88fc46c4b5f1e01
3 | containsDevices: 1
4 | baseType: DistanceSensor
5 | slotType:
6 | parameters: translation,rotation,name,type
7 | tags:
8 | license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
9 | licenseUrl: https://cyberbotics.com/webots_assets_license
10 | documentationUrl:
11 | info: Distance\ssensor\sof\sthe\sPioneer\s3AT\srobot.\n
12 |
--------------------------------------------------------------------------------
/protos/.Pioneer3Gripper.cache:
--------------------------------------------------------------------------------
1 | Webots Proto Cache File version 1.4
2 | protoFileHash: b82fa35c62cd1daec78e1700d90d04a0
3 | containsDevices: 1
4 | baseType: Solid
5 | slotType:
6 | parameters: translation,name
7 | tags:
8 | license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
9 | licenseUrl: https://cyberbotics.com/webots_assets_license
10 | documentationUrl:
11 | info: Physics-based\smodel\sof\sthe\sPioneer\sgripper\s(Adept\sMobile\sRobotics)\n
12 |
--------------------------------------------------------------------------------
/protos/.Pioneer3at.cache:
--------------------------------------------------------------------------------
1 | Webots Proto Cache File version 1.4
2 | protoFileHash: 438f5a6be6d43f033d988b4275885f3b
3 | containsDevices: 1
4 | baseType: Robot
5 | slotType:
6 | parameters: translation,rotation,name,controller,controllerArgs,customData,supervisor,synchronization,extensionSlot
7 | tags:
8 | license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
9 | licenseUrl: https://cyberbotics.com/webots_assets_license
10 | documentationUrl: https://www.cyberbotics.com/doc/guide/pioneer-3at
11 | info: Pioneer\s3AT\srobot\s(Adept\sMobileRobots)\sis\san\sall\sterrain\sfour\swheels\sdrive\srobot.\n
12 |
--------------------------------------------------------------------------------
/protos/.Pioneer3dx.cache:
--------------------------------------------------------------------------------
1 | Webots Proto Cache File version 1.4
2 | protoFileHash: fe8538695035c9cee6a7eeeceff71988
3 | containsDevices: 1
4 | baseType: Robot
5 | slotType:
6 | parameters: translation,rotation,name,controller,controllerArgs,customData,supervisor,synchronization,extensionSlot
7 | tags:
8 | license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
9 | licenseUrl: https://cyberbotics.com/webots_assets_license
10 | documentationUrl: https://www.cyberbotics.com/doc/guide/pioneer-3dx
11 | info: The\sPioneer\s3-DX\srobot\s(Adept\sMobileRobots)\sis\san\sall-purpose\sbase,\sused\sfor\sresearch\sand\sapplications\sinvolving\smapping,\steleoperation,\slocalization,\smonitoring,\sreconnaissance\sand\sother\sbehaviors.\n
12 |
--------------------------------------------------------------------------------
/protos/.RectangleArena.cache:
--------------------------------------------------------------------------------
1 | Webots Proto Cache File version 1.4
2 | protoFileHash: ce6509592b6a95b47ec579a7e7f439d9
3 | containsDevices: 0
4 | baseType: Solid
5 | slotType:
6 | parameters: translation,rotation,name,contactMaterial,floorSize,floorTileSize,floorAppearance,wallThickness,wallHeight,wallAppearance,floorTextureUrl,wallTextureUrl,wallColor,wallTileSize
7 | tags: static
8 | license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
9 | licenseUrl: https://cyberbotics.com/webots_assets_license
10 | documentationUrl:
11 | info: A\sconfigurable\srectangle\sarena\scomposed\sof\sa\sfloor\ssurrounded\sby\swalls.\n
12 |
--------------------------------------------------------------------------------
/protos/.SandyGround.cache:
--------------------------------------------------------------------------------
1 | Webots Proto Cache File version 1.4
2 | protoFileHash: 46af411fc55179b6b9bd8f1581aef07e
3 | containsDevices: 0
4 | baseType: PBRAppearance
5 | slotType:
6 | parameters: colorOverride,textureTransform,IBLStrength
7 | tags:
8 | license: Apache License 2.0
9 | licenseUrl: http://www.apache.org/licenses/LICENSE-2.0
10 | documentationUrl:
11 | info: A\ssandy\sground\smaterial.\sThe\scolor\scan\sbe\sselected\susing\sthe\s`colorOverride`\sfield.\sUseful\swith\sthe\sUnevenTerrain\sPROTO.\n
12 |
--------------------------------------------------------------------------------
/protos/.UnevenTerrain.cache:
--------------------------------------------------------------------------------
1 | Webots Proto Cache File version 1.4
2 | protoFileHash: 7d9b2002f95626c59ac8680da2dc49cb
3 | containsDevices: 0
4 | baseType: Solid
5 | slotType:
6 | parameters: translation,rotation,name,size,xDimension,zDimension,appearance,textureScale,randomSeed,flatCenter,flatBounds,perlinNOctaves,texture
7 | tags:
8 | license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
9 | licenseUrl: https://cyberbotics.com/webots_assets_license
10 | documentationUrl:
11 | info: Randomly\sgenerated\suneven\sterrain\sbased\son\sPerlin\snoise.\n
12 |
--------------------------------------------------------------------------------
/protos/CircleArena.proto:
--------------------------------------------------------------------------------
1 | #VRML_SIM R2019b utf8
2 | # license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
3 | # license url: https://cyberbotics.com/webots_assets_license
4 | # tags: static
5 | # A configurable circle arena composed of floor surrounded by wall.
6 |
7 | PROTO CircleArena [
8 | field SFVec3f translation 0 0 0
9 | field SFRotation rotation 0 1 0 0
10 | field SFString name "circle arena"
11 | field SFFloat radius 1.0 # Defines the radius of the arena.
12 | field SFString contactMaterial "default" # Is `Solid.contactMaterial`.
13 | field SFNode floorAppearance ChequeredParquetry {} # Defines the appearance of the floor.
14 | field SFVec2f floorTileSize 0.5 0.5 # Defines the size of the texture used for the floor.
15 | field SFFloat wallThickness 0.01 # Defines the thickness of the wall.
16 | field SFFloat wallHeight 0.1 # Defines the height of the wall.
17 | field SFNode wallAppearance BrushedAluminium {} # Defines the appearance of the wall.
18 | field SFInt32 subdivision 48 # Defines the subdivision of the wall cylinder.
19 |
20 | # Deprecated in R2019a
21 | hiddenField MFString floorTextureUrl "textures/checkered_parquetry.jpg"
22 | hiddenField MFString wallTextureUrl "textures/metal.jpg"
23 | # Deprecated in R2019-rev2
24 | hiddenField SFVec2f wallTileSize 0.5 0.5
25 |
26 | ]
27 | {
28 | %{
29 | local wbgeometry = require('wbgeometry')
30 |
31 | if fields.floorTextureUrl.value[0] ~= fields.floorTextureUrl.defaultValue[0] then
32 | io.stderr:write("The 'floorTextureUrl' field is deprecated, using the new 'floorAppearance' field instead.\n")
33 | end
34 |
35 | if fields.wallTextureUrl.value[0] ~= fields.wallTextureUrl.defaultValue[0] then
36 | io.stderr:write("The 'wallTextureUrl' field is deprecated, using the new 'wallAppearance' field instead.\n")
37 | end
38 |
39 | if (fields.wallTileSize.value.x ~= fields.wallTileSize.defaultValue.x or
40 | fields.wallTileSize.value.y ~= fields.wallTileSize.defaultValue.y) then
41 | io.stderr:write("The 'wallTileSize' field is deprecated, using the new 'wallAppearance' field instead.\n")
42 | end
43 |
44 | local subdivision = fields.subdivision.value
45 | if subdivision <= 8 then
46 | io.stderr:write("'subdivision' must be greater than 8\n")
47 | subdivision = 8
48 | end
49 |
50 | local radius = fields.radius.value
51 | if radius <= 0.0 then
52 | io.stderr:write("'radius' must be positive\n")
53 | radius = fields.radius.defaultValue
54 | end
55 |
56 | local wallThickness = fields.wallThickness.value
57 | if wallThickness <= 0 then
58 | io.stderr:write("'wallThickness' must be positive\n")
59 | wallThickness = fields.wallThickness.defaultValue
60 | end
61 |
62 | local wallHeight = fields.wallHeight.value
63 | if wallHeight <= 0 then
64 | io.stderr:write("'wallHeight' must be positive\n")
65 | wallHeight = fields.wallHeight.defaultValue
66 | end
67 |
68 | realRadius = radius + wallThickness / 2
69 |
70 | local floorTextureScale = { x = 1; y = 1 }
71 | if fields.floorTileSize.value.x >= 0 and fields.floorTileSize.value.y > 0.0 then -- avoid a zero division and negative values
72 | floorTextureScale.x = fields.floorTileSize.value.x
73 | floorTextureScale.y = fields.floorTileSize.value.y
74 | else
75 | io.stderr:write("'floorTextureScale' must contain positive values\n")
76 | end
77 | }%
78 | Solid {
79 | translation IS translation
80 | rotation IS rotation
81 | children [
82 | SolidPipe {
83 | translation 0 %{= wallHeight / 2 }% 0
84 | height %{= wallHeight }%
85 | radius %{= radius + wallThickness }%
86 | thickness %{= wallThickness }%
87 | subdivision %{= subdivision }%
88 | contactMaterial IS contactMaterial
89 | appearance IS wallAppearance
90 | }
91 | Shape {
92 | appearance IS floorAppearance
93 | geometry IndexedFaceSet {
94 | %{ local circle = wbgeometry.circle(realRadius, subdivision, 0, 0, 0) }%
95 | coord Coordinate {
96 | point [
97 | %{ for i, el in ipairs(circle) do }%
98 | %{= el.x }% %{= 0 }% %{= el.y }%
99 | %{ end }%
100 | ]
101 | }
102 | texCoord TextureCoordinate {
103 | point [
104 | %{ for i, el in ipairs(circle) do }%
105 | %{= el.x / floorTextureScale.x }% %{= el.y / floorTextureScale.y}%
106 | %{ end }%
107 | ]
108 | }
109 | coordIndex [
110 | %{ for j = subdivision, 0, -1 do }%
111 | %{= j }%
112 | %{ end }%
113 | -1
114 | ]
115 | texCoordIndex [
116 | %{ for j = subdivision, 0, -1 do }%
117 | %{= j }%
118 | %{ end }%
119 | -1
120 | ]
121 | }
122 | }
123 | ]
124 | name IS name
125 | model "circle arena"
126 | boundingObject Plane {
127 | size %{= 2 * radius }% %{= 2 * radius }%
128 | }
129 | contactMaterial IS contactMaterial
130 | locked TRUE
131 | }
132 | }
133 |
--------------------------------------------------------------------------------
/protos/Floor.proto:
--------------------------------------------------------------------------------
1 | #VRML_SIM R2019b utf8
2 | # license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
3 | # license url: https://cyberbotics.com/webots_assets_license
4 | # tags: static
5 | # Configurable standard flat floor.
6 |
7 | PROTO Floor [
8 | field SFVec3f translation 0 0 0
9 | field SFRotation rotation 0 1 0 0
10 | field SFString name "floor"
11 | field SFString contactMaterial "default" # Is `Solid.contactMaterial`.
12 | field SFVec2f size 10 10 # Defines the size of the floor.
13 | field SFVec2f tileSize 0.5 0.5 # Defines the size of texture used for the floor.
14 | field SFNode appearance SandyGround {} # Defines the appearance of the floor.
15 |
16 | # Deprecated in R2019a
17 | hiddenField MFString texture "textures/rover_circuit.jpg"
18 | ]
19 | {
20 | %{
21 | local wbmath = require('wbmath')
22 |
23 | local size = fields.size.value
24 | if size.x <= 0 or size.y <= 0 then
25 | size = fields.size.defaultValue
26 | io.stderr:write("'size' must contain positive values\n")
27 | end
28 |
29 | local texture = fields.texture.value[0]
30 | if texture ~= fields.texture.defaultValue[0] then
31 | io.stderr:write("The 'texture' field is deprecated, using the new 'appearance' field instead.\n")
32 | end
33 |
34 | local tileSize = fields.tileSize.value
35 | if tileSize.x <= 0 or tileSize.y <= 0 then -- avoid a zero division and negative values
36 | tileSize = fields.tileSize.defaultValue
37 | io.stderr:write("'tileScale' must contain positive values\n")
38 | end
39 | local textureScale = { x = size.x / tileSize.x, y = size.y / tileSize.y }
40 | }%
41 | Solid {
42 | translation IS translation
43 | rotation IS rotation
44 | children [
45 | Shape {
46 | appearance IS appearance
47 | geometry IndexedFaceSet {
48 | coord Coordinate {
49 | point [
50 | %{= -(size.x / 2) }% 0 %{= -(size.y / 2) }%
51 | %{= size.x / 2 }% 0 %{= -(size.y / 2) }%
52 | %{= -(size.x / 2) }% 0 %{= size.y / 2 }%
53 | %{= size.x / 2 }% 0 %{= size.y / 2 }%
54 | ]
55 | }
56 | texCoord TextureCoordinate {
57 | point [
58 | 0 0
59 | %{= textureScale.x }% 0
60 | 0 %{= textureScale.y }%
61 | %{= textureScale.x }% %{= textureScale.y }%
62 | ]
63 | }
64 | coordIndex [
65 | 0 2 3 1 -1
66 | ]
67 | texCoordIndex [
68 | 2 0 1 3 -1
69 | ]
70 | }
71 | }
72 | ]
73 | name IS name
74 | model "floor"
75 | boundingObject Plane {
76 | size IS size
77 | }
78 | contactMaterial IS contactMaterial
79 | locked TRUE
80 | }
81 | }
82 |
--------------------------------------------------------------------------------
/protos/Pioneer3DistanceSensor.proto:
--------------------------------------------------------------------------------
1 | #VRML_SIM R2019b utf8
2 | # license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
3 | # license url: https://cyberbotics.com/webots_assets_license
4 | # Distance sensor of the Pioneer 3AT robot.
5 |
6 | PROTO Pioneer3DistanceSensor [
7 | field SFVec3f translation 0 0.137 0
8 | field SFRotation rotation 0 1 0 0
9 | field SFString name "so"
10 | field SFString type "sonar"
11 | ]
12 | {
13 | DistanceSensor {
14 | translation IS translation
15 | rotation IS rotation
16 | name IS name
17 | model "Pioneer3 distance sensor"
18 | type IS type
19 | children [
20 | DEF BLACK_BODY_SHAPE Shape {
21 | appearance PBRAppearance {
22 | baseColor 0 0 0
23 | roughness 0.2
24 | metalness 0
25 | }
26 | geometry IndexedFaceSet {
27 | coord Coordinate {
28 | point [
29 | 0.0027176 -0.0082813 -0.0199851, 0.0027176 -0.0152989 -0.0152947
30 | 0.0027176 -0.0199874 -0.0082758, 0.0027176 -0.021633 3e-06
31 | 0.0027176 -0.0199851 0.0082813, 0.0027176 -0.0152947 0.0152989
32 | 0.0027176 -0.0082758 0.0199874, 0.0027176 3e-06 0.021633
33 | 0.0027176 0.0082813 0.0199851, 0.0027176 0.0152989 0.0152947
34 | 0.0027176 0.0199874 0.0082758, 0.0027176 0.021633 -3e-06
35 | 0.0027176 0.0199851 -0.0082813, 0.0027176 0.0152947 -0.0152989
36 | 0.0027176 0.0082758 -0.0199874, 0.0027176 -3e-06 -0.021633
37 | 3.68e-05 -0.0082813 -0.0199851, 3.68e-05 -0.0152989 -0.0152947
38 | 3.68e-05 -0.0199874 -0.0082758, 3.68e-05 -0.021633 3e-06
39 | 3.68e-05 -0.0199851 0.0082813, 3.68e-05 -0.0152947 0.0152989
40 | 3.68e-05 -0.0082758 0.0199874, 3.68e-05 3e-06 0.021633
41 | 3.68e-05 0.0082813 0.0199851, 3.68e-05 0.0152989 0.0152947
42 | 3.68e-05 0.0199874 0.0082758, 3.68e-05 0.021633 -3e-06
43 | 3.68e-05 0.0199851 -0.0082813, 3.68e-05 0.0152947 -0.0152989
44 | 3.68e-05 0.0082758 -0.0199874, 3.68e-05 -3e-06 -0.021633
45 | 0.0027176 -0.0071569 -0.0172717, 0.0027176 -0.0132217 -0.0132181
46 | 0.0027176 -0.0172736 -0.0071522, 0.0027176 -0.0186958 2.6e-06
47 | 0.0027176 -0.0172717 0.0071569, 0.0027176 -0.0132181 0.0132217
48 | 0.0027176 -0.0071522 0.0172736, 0.0027176 2.6e-06 0.0186958
49 | 0.0027176 0.0071569 0.0172717, 0.0027176 0.0132217 0.0132181
50 | 0.0027176 0.0172736 0.0071522, 0.0027176 0.0186958 -2.6e-06
51 | 0.0027176 0.0172717 -0.0071569, 0.0027176 0.0132181 -0.0132217
52 | 0.0027176 0.0071522 -0.0172736, 0.0027176 -2.6e-06 -0.0186958
53 | 0.0004008 -0.0071569 -0.0172717, 0.0004008 -0.0132217 -0.0132181
54 | 0.0004008 -0.0172736 -0.0071522, 0.0004008 -0.0186958 2.6e-06
55 | 0.0004008 -0.0172717 0.0071569, 0.0004008 -0.0132181 0.0132217
56 | 0.0004008 -0.0071522 0.0172736, 0.0004008 2.6e-06 0.0186958
57 | 0.0004008 0.0071569 0.0172717, 0.0004008 0.0132217 0.0132181
58 | 0.0004008 0.0172736 0.0071522, 0.0004008 0.0186958 -2.6e-06
59 | 0.0004008 0.0172717 -0.0071569, 0.0004008 0.0132181 -0.0132217
60 | 0.0004008 0.0071522 -0.0172736, 0.0004008 -2.6e-06 -0.0186958
61 | ]
62 | }
63 | coordIndex [
64 | 63 46 62 -1 63 47 46 -1 61 62 46 -1
65 | 61 46 45 -1 60 61 45 -1 60 45 44 -1
66 | 60 44 43 -1 60 43 59 -1 59 43 42 -1
67 | 59 42 58 -1 57 58 42 -1 57 42 41 -1
68 | 56 57 41 -1 56 41 40 -1 56 40 39 -1
69 | 56 39 55 -1 55 39 38 -1 55 38 54 -1
70 | 53 54 38 -1 53 38 37 -1 52 53 37 -1
71 | 52 37 36 -1 52 36 35 -1 52 35 51 -1
72 | 51 35 34 -1 51 34 50 -1 49 50 34 -1
73 | 49 34 33 -1 49 33 32 -1 49 32 48 -1
74 | 15 14 46 -1 15 46 47 -1 13 45 46 -1
75 | 13 46 14 -1 12 44 45 -1 12 45 13 -1
76 | 12 11 43 -1 12 43 44 -1 11 10 42 -1
77 | 11 42 43 -1 9 41 42 -1 9 42 10 -1
78 | 8 40 41 -1 8 41 9 -1 8 7 39 -1
79 | 8 39 40 -1 7 6 38 -1 7 38 39 -1
80 | 5 37 38 -1 5 38 6 -1 4 36 37 -1
81 | 4 37 5 -1 4 3 35 -1 4 35 36 -1
82 | 3 2 34 -1 3 34 35 -1 1 33 34 -1
83 | 1 34 2 -1 1 0 32 -1 1 32 33 -1
84 | 15 47 32 -1 32 0 15 -1 14 15 31 -1
85 | 14 31 30 -1 14 30 29 -1 14 29 13 -1
86 | 13 29 28 -1 13 28 12 -1 11 12 28 -1
87 | 11 28 27 -1 10 11 27 -1 10 27 26 -1
88 | 10 26 25 -1 10 25 9 -1 9 25 24 -1
89 | 9 24 8 -1 7 8 24 -1 7 24 23 -1
90 | 6 7 23 -1 6 23 22 -1 6 22 21 -1
91 | 6 21 5 -1 5 21 20 -1 5 20 4 -1
92 | 3 4 20 -1 3 20 19 -1 2 3 19 -1
93 | 2 19 18 -1 2 18 17 -1 2 17 1 -1
94 | 0 1 17 -1 0 17 16 -1 0 16 31 -1
95 | 0 31 15 -1 47 48 32 -1 47 63 48 -1
96 | ]
97 | creaseAngle 1
98 | }
99 | }
100 | DEF BOTTOM_DISC_SHAPE Shape {
101 | appearance PBRAppearance {
102 | baseColorMap ImageTexture {
103 | url [
104 | "textures/honeycomb_base_color.jpg"
105 | ]
106 | }
107 | normalMap ImageTexture {
108 | url [
109 | "textures/honeycomb_normal.jpg"
110 | ]
111 | }
112 | roughness 0.4
113 | }
114 | geometry IndexedFaceSet {
115 | coord DEF coord_BOTTOM_DISC Coordinate {
116 | point [
117 | 0.0001602 3.59e-05 0.0196526, 0.0001602 -0.0075108 0.0181533
118 | 0.0001602 -0.0139092 0.0138801, 0.0001602 -0.0181854 0.0074836
119 | 0.0001602 0.0075819 0.0181497, 0.0001602 0.0139783 0.0138736
120 | 0.0001602 0.0182515 0.0074751, 0.0001602 0.0197508 -7.15e-05
121 | 0.0001602 0.018248 -0.0076175, 0.0001602 0.0139718 -0.014014
122 | 0.0001602 0.0075734 -0.0182871, 0.0001602 2.67e-05 -0.0197864
123 | 0.0001602 -0.0075193 -0.0182836, 0.0001602 -0.0139157 -0.0140075
124 | 0.0001602 -0.0181889 -0.007609, 0.0001602 -0.0196882 -6.23e-05
125 | ]
126 | }
127 | texCoord TextureCoordinate {
128 | point [
129 | 0.404999 0.9776, 0.229461 0.90489, 0.09511 0.770539
130 | 0.404999 0.9776, 0.09511 0.770539, 0.0223996 0.595001
131 | 0.595 0.9776, 0.404999 0.9776, 0.0223996 0.595001
132 | 0.595 0.9776, 0.0223996 0.595001, 0.0223995 0.405
133 | 0.770539 0.90489, 0.595 0.9776, 0.0223995 0.405
134 | 0.0223995 0.405, 0.0951098 0.229461, 0.770539 0.90489
135 | 0.770539 0.90489, 0.0951098 0.229461, 0.90489 0.770539
136 | 0.90489 0.770539, 0.0951098 0.229461, 0.229461 0.09511
137 | 0.9776 0.595001, 0.90489 0.770539, 0.229461 0.09511
138 | 0.9776 0.595001, 0.229461 0.09511, 0.405 0.0223995
139 | 0.9776 0.405, 0.9776 0.595001, 0.405 0.0223995
140 | 0.9776 0.405, 0.405 0.0223995, 0.595001 0.0223997
141 | 0.90489 0.229462, 0.9776 0.405, 0.595001 0.0223997
142 | 0.90489 0.229462, 0.595001 0.0223997, 0.770539 0.0951104
143 | ]
144 | }
145 | coordIndex [
146 | 8 7 6 -1 8 6 5 -1 9 8 5 -1
147 | 9 5 4 -1 10 9 4 -1 4 0 10 -1
148 | 10 0 11 -1 11 0 1 -1 12 11 1 -1
149 | 12 1 2 -1 13 12 2 -1 13 2 3 -1
150 | 14 13 3 -1 14 3 15 -1
151 | ]
152 | texCoordIndex [
153 | 0 1 2 -1 3 4 5 -1 6 7 8 -1
154 | 9 10 11 -1 12 13 14 -1 15 16 17 -1
155 | 18 19 20 -1 21 22 23 -1 24 25 26 -1
156 | 27 28 29 -1 30 31 32 -1 33 34 35 -1
157 | 36 37 38 -1 39 40 41 -1
158 | ]
159 | creaseAngle 1
160 | }
161 | }
162 | DEF SONAR_GLASS_SHAPE Shape {
163 | appearance PBRAppearance {
164 | metalness 0
165 | transparency 0.8
166 | }
167 | geometry IndexedFaceSet {
168 | coord Coordinate {
169 | point [
170 | 0.0022441 -0.0078844 -0.017925, 0.0022441 -0.014335 -0.0136148
171 | 0.0022441 -0.0186452 -0.0071641, 0.0022441 -0.0201588 0.0004449
172 | 0.0022441 -0.0186452 0.008054, 0.0022441 -0.014335 0.0145046
173 | 0.0022441 -0.0078844 0.0188148, 0.0022441 -0.0002753 0.0203284
174 | 0.0022441 0.0073338 0.0188148, 0.0022441 0.0137844 0.0145046
175 | 0.0022441 0.0180946 0.008054, 0.0022441 0.0196081 0.0004449
176 | 0.0022441 0.0180946 -0.0071642, 0.0022441 0.0137844 -0.0136148
177 | 0.0022441 0.0073337 -0.017925, 0.0022441 -0.0002753 -0.0194385
178 | ]
179 | }
180 | coordIndex [
181 | 12 11 10 -1 12 10 9 -1 13 12 9 -1
182 | 13 9 8 -1 14 13 8 -1 14 8 7 -1
183 | 15 14 7 -1 15 7 6 -1 0 15 6 -1
184 | 0 6 5 -1 1 0 5 -1 1 5 4 -1
185 | 2 1 4 -1 2 4 3 -1
186 | ]
187 | creaseAngle 1
188 | }
189 | }
190 | ]
191 | lookupTable [
192 | 0 1024 0.01,
193 | 5 0 0.01
194 | ]
195 | }
196 | }
197 |
--------------------------------------------------------------------------------
/protos/Pioneer3Gripper.proto:
--------------------------------------------------------------------------------
1 | #VRML_SIM R2019b utf8
2 | # license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
3 | # license url: https://cyberbotics.com/webots_assets_license
4 | # Physics-based model of the Pioneer gripper (Adept Mobile Robotics)
5 |
6 | PROTO Pioneer3Gripper [
7 | field SFVec3f translation 0 0 0
8 | field SFString name "Pioneer3 gripper"
9 | ]
10 | {
11 | DEF GRIPPER_BASE Solid {
12 | translation IS translation
13 | children [
14 | DEF LIFT_SLIDER SliderJoint {
15 | jointParameters JointParameters {
16 | axis 0 -1 0
17 | }
18 | device LinearMotor {
19 | name "lift motor"
20 | minPosition -0.05
21 | maxPosition 0.05
22 | }
23 | endPoint DEF LIFT Solid {
24 | translation 0 0 -0.0425
25 | children [
26 | DEF LEFT_FINGER_SLIDER SliderJoint {
27 | jointParameters JointParameters {
28 | axis -1 0 0
29 | }
30 | device LinearMotor {
31 | name "left finger motor"
32 | maxPosition 0.1
33 | }
34 | endPoint DEF LEFT_FINGER Solid {
35 | translation -0.022 0 -0.02
36 | children [
37 | Group {
38 | children [
39 | Transform {
40 | translation 0 0.0015 -0.003
41 | children [
42 | Shape {
43 | appearance DEF METAL_APPEARANCE PBRAppearance {
44 | roughness 0.2
45 | baseColorMap ImageTexture {
46 | url [
47 | "textures/metal.jpg"
48 | ]
49 | }
50 | }
51 | geometry Box {
52 | size 0.018 0.031 0.036
53 | }
54 | }
55 | ]
56 | }
57 | DEF LEFT_FINGER_TRANSFORM Transform {
58 | translation 0.0015 -0.006 -0.069
59 | children [
60 | Shape {
61 | appearance DEF BLACK_APPEARANCE PBRAppearance {
62 | baseColor 0.0705882 0.0705882 0.0705882
63 | metalness 0
64 | roughness 0.4
65 | }
66 | geometry Box {
67 | size 0.015 0.035 0.095
68 | }
69 | }
70 | ]
71 | }
72 | ]
73 | }
74 | ]
75 | name "left finger"
76 | physics DEF LEFT_FINGER_PHYSICS Physics {
77 | }
78 | boundingObject USE LEFT_FINGER_TRANSFORM
79 | }
80 | }
81 | DEF RIGHT_FINGER_SLIDER SliderJoint {
82 | jointParameters JointParameters {
83 | axis 1 0 0
84 | }
85 | device LinearMotor {
86 | name "right finger motor"
87 | maxPosition 0.1
88 | }
89 | endPoint DEF RIGHT_FINGER Solid {
90 | translation 0.022 0 -0.02
91 | children [
92 | Group {
93 | children [
94 | Transform {
95 | translation 0 0.0015 -0.003
96 | children [
97 | Shape {
98 | appearance USE METAL_APPEARANCE
99 | geometry Box {
100 | size 0.018 0.031 0.036
101 | }
102 | }
103 | ]
104 | }
105 | DEF RIGHT_FINGER_TRANSFORM Transform {
106 | translation -0.0015 -0.006 -0.069
107 | children [
108 | Shape {
109 | appearance USE BLACK_APPEARANCE
110 | geometry Box {
111 | size 0.015 0.035 0.095
112 | }
113 | }
114 | ]
115 | }
116 | ]
117 | }
118 | ]
119 | name "right finger"
120 | physics USE LEFT_FINGER_PHYSICS
121 | boundingObject USE RIGHT_FINGER_TRANSFORM
122 | }
123 | }
124 | Transform {
125 | translation 0 -0.126 0.135
126 | children [
127 | Group {
128 | children [
129 | Transform {
130 | translation 0 0.1478 -0.154
131 | children [
132 | DEF UPPER_BOX Shape {
133 | appearance USE BLACK_APPEARANCE
134 | geometry Box {
135 | size 0.315 0.01 0.043419
136 | }
137 | }
138 | ]
139 | }
140 | Transform {
141 | translation 0 0.1072 -0.154
142 | children [
143 | USE UPPER_BOX
144 | ]
145 | }
146 | Transform {
147 | translation -0.155 0.1275 -0.154
148 | children [
149 | DEF LEFT_BOX Shape {
150 | appearance USE BLACK_APPEARANCE
151 | geometry Box {
152 | size 0.007 0.05 0.042227
153 | }
154 | }
155 | ]
156 | }
157 | Transform {
158 | translation 0.155 0.1275 -0.154
159 | children [
160 | USE LEFT_BOX
161 | ]
162 | }
163 | Transform {
164 | translation 0 0.126 -0.158
165 | children [
166 | DEF CENTER_BOX Shape {
167 | appearance USE BLACK_APPEARANCE
168 | geometry Box {
169 | size 0.027 0.0341 0.035
170 | }
171 | }
172 | ]
173 | }
174 | Transform {
175 | translation 0 0.132 -0.154
176 | rotation 0 0 1 1.5708
177 | children [
178 | DEF UPPER_CYLINDER Shape {
179 | appearance USE METAL_APPEARANCE
180 | geometry Cylinder {
181 | height 0.3
182 | radius 0.00225
183 | }
184 | }
185 | ]
186 | }
187 | Transform {
188 | translation 0 0.118 -0.154
189 | rotation 0 0 1 1.5708
190 | children [
191 | Shape {
192 | appearance USE METAL_APPEARANCE
193 | geometry Cylinder {
194 | height 0.3
195 | radius 0.00125
196 | }
197 | }
198 | ]
199 | }
200 | Transform {
201 | translation -0.041 0.155 -0.148
202 | children [
203 | Shape {
204 | appearance USE BLACK_APPEARANCE
205 | geometry Box {
206 | size 0.0141907 0.006 0.04
207 | }
208 | }
209 | ]
210 | }
211 | Transform {
212 | translation -0.036 0.145 -0.116
213 | children [
214 | Shape {
215 | appearance USE METAL_APPEARANCE
216 | geometry Box {
217 | size 0.027 0.03 0.03
218 | }
219 | }
220 | ]
221 | }
222 | Transform {
223 | translation 0.041 0.155 -0.148
224 | children [
225 | Shape {
226 | appearance USE BLACK_APPEARANCE
227 | geometry Box {
228 | size 0.0141907 0.006 0.04
229 | }
230 | }
231 | ]
232 | }
233 | Transform {
234 | translation 0.036 0.145 -0.116
235 | children [
236 | Shape {
237 | appearance USE METAL_APPEARANCE
238 | geometry Box {
239 | size 0.027 0.03 0.03
240 | }
241 | }
242 | ]
243 | }
244 | ]
245 | }
246 | ]
247 | }
248 | ]
249 | boundingObject Transform {
250 | translation 0 0.0015 -0.019
251 | children [
252 | Shape {
253 | appearance USE METAL_APPEARANCE
254 | geometry Box {
255 | size 0.315 0.05 0.045
256 | }
257 | }
258 | ]
259 | }
260 | physics DEF LIFT_PHYSICS Physics {
261 | }
262 | }
263 | }
264 | Transform {
265 | translation 0 -0.126 0.135
266 | children [
267 | DEF BASE_SHAPE_GROUP Group {
268 | children [
269 | Transform {
270 | translation 0 0.176 -0.154
271 | children [
272 | DEF UPPER_BOX Shape {
273 | appearance USE BLACK_APPEARANCE
274 | geometry Box {
275 | size 0.141092 0.0170038 0.043419
276 | }
277 | }
278 | ]
279 | }
280 | Transform {
281 | translation 0 0.075 -0.154
282 | children [
283 | USE UPPER_BOX
284 | ]
285 | }
286 | Transform {
287 | translation -0.06 0.126 -0.158
288 | children [
289 | DEF LEFT_BOX Shape {
290 | appearance USE BLACK_APPEARANCE
291 | geometry Box {
292 | size 0.02 0.0875 0.035
293 | }
294 | }
295 | ]
296 | }
297 | Transform {
298 | translation 0.06 0.126 -0.158
299 | children [
300 | USE LEFT_BOX
301 | ]
302 | }
303 | Transform {
304 | translation 0 0.126 -0.158
305 | children [
306 | DEF CENTER_BOX Shape {
307 | appearance USE BLACK_APPEARANCE
308 | geometry Box {
309 | size 0.044 0.1 0.0315
310 | }
311 | }
312 | ]
313 | }
314 | Transform {
315 | translation -0.037 0.126 -0.158
316 | children [
317 | DEF LEFT_CYLINDER Shape {
318 | appearance USE METAL_APPEARANCE
319 | geometry Cylinder {
320 | height 0.1
321 | radius 0.003
322 | }
323 | }
324 | ]
325 | }
326 | Transform {
327 | translation 0.037 0.126 -0.158
328 | children [
329 | USE LEFT_CYLINDER
330 | ]
331 | }
332 | ]
333 | }
334 | ]
335 | }
336 | ]
337 | name IS name
338 | model "Pioneer3 gripper"
339 | boundingObject Transform {
340 | translation 0 0 -0.019
341 | children [
342 | Box {
343 | size 0.141 0.117 0.043
344 | }
345 | ]
346 | }
347 | physics DEF BASE_PHYSICS Physics {
348 | }
349 | }
350 | }
351 |
--------------------------------------------------------------------------------
/protos/Pioneer3dx.proto:
--------------------------------------------------------------------------------
1 | #VRML_SIM R2019b utf8
2 | # license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
3 | # license url: https://cyberbotics.com/webots_assets_license
4 | # documentation url: https://www.cyberbotics.com/doc/guide/pioneer-3dx
5 | # The Pioneer 3-DX robot (Adept MobileRobots) is an all-purpose base, used for research and applications involving mapping, teleoperation, localization, monitoring, reconnaissance and other behaviors.
6 |
7 | PROTO Pioneer3dx [
8 | field SFVec3f translation 0 0.0975 0 # Is `Transform.translation`.
9 | field SFRotation rotation 0 1 0 0 # Is `Transform.rotation`.
10 | field SFString name "Pioneer 3-DX" # Is `Solid.name`.
11 | field SFString controller "pioneer3dx_collision_avoidance" # Is `Robot.controller`.
12 | field SFString controllerArgs "" # Is `Robot.controllerArgs`.
13 | field SFString customData "" # Is `Robot.customData`.
14 | field SFBool supervisor FALSE # Is `Robot.supervisor`.
15 | field SFBool synchronization TRUE # Is `Robot.synchronization`.
16 | field MFNode extensionSlot [] # Extends the robot with new nodes in the extension slot.
17 | ]
18 | {
19 | Robot {
20 | translation IS translation
21 | rotation IS rotation
22 | children [
23 | DEF BODY Transform {
24 | rotation 1 0 0 0
25 | children [
26 | DEF BAR Transform {
27 | translation 0.0001812 0.0403308 0.231994
28 | rotation 1 0 0 0
29 | children [
30 | DEF BAR_SHAPE Shape {
31 | appearance PBRAppearance {
32 | baseColor 0 0 0
33 | metalness 0
34 | roughness 0.3
35 | }
36 | geometry IndexedFaceSet {
37 | coord DEF coord_barIFS Coordinate {
38 | point [
39 | 0.0584591 -0.0043278 0.0147324, 0.0574447 -0.0022654 0.0116106 0.0573106 0.0015867 0.0111979, 0.0581577 0.0043279 0.0138048 0.0593482 0.0038938 0.0174684, 0.0599853 0.0006115 0.0194299 0.0595898 -0.0030475 0.0182122, 0.0630086 -0.0030475 0.016456 0.0637612 0.0006115 0.0174918, 0.0625489 0.0038938 0.0158233 0.0602847 0.0043279 0.0127069, 0.0586736 0.0015867 0.0104892 0.0589285 -0.0022654 0.0108403, 0.0608579 -0.0043278 0.0134958 0.0627572 -0.0043278 0.0115786, 0.0601018 -0.0022654 0.0096492 0.0597505 0.0015867 0.0093942, 0.0619683 0.0043279 0.0110053 0.0650847 0.0038938 0.0132696, 0.0667532 0.0006115 0.0144818 0.0657174 -0.0030475 0.0137294, 0.0674511 -0.0030475 0.0102989 0.0686687 0.0006115 0.0106945, 0.0667073 0.0038938 0.0100572 0.0630437 0.0043279 0.0088668, 0.0604367 0.0015867 0.0080197 0.0608495 -0.0022654 0.0081539, 0.0639711 -0.0043278 0.0091683 0.0643808 -0.0043278 -0.0201063, 0.0610984 -0.0022654 -0.0201064 0.0606644 0.0015868 -0.0201063, 0.0634057 0.0043279 -0.0201064 0.0672576 0.0038938 -0.0201064, 0.06932 0.0006115 -0.0201063 0.0680396 -0.0030475 -0.0201063, -0.0680396 -0.0030476 -0.0201063 -0.06932 0.0006114 -0.0201063, -0.0672576 0.0038938 -0.0201063 -0.0634056 0.0043278 -0.0201063, -0.0606643 0.0015867 -0.0201063 -0.0610984 -0.0022655 -0.0201063, -0.0643808 -0.0043279 -0.0201063 -0.0639711 -0.0043279 0.0091682, -0.0608495 -0.0022655 0.0081539 -0.0604367 0.0015867 0.0080198, -0.0630437 0.0043278 0.0088668 -0.0667074 0.0038938 0.0100572, -0.0686687 0.0006114 0.0106945 -0.0674511 -0.0030476 0.0102989, -0.0657174 -0.0030476 0.0137293 -0.0667532 0.0006114 0.0144818, -0.0650848 0.0038938 0.0132695 -0.0619683 0.0043278 0.0110053, -0.0597505 0.0015867 0.0093942 -0.0601018 -0.0022655 0.0096493, -0.0627573 -0.0043279 0.0115785 -0.060858 -0.0043279 0.0134958, -0.0589286 -0.0022655 0.0108404 -0.0586737 0.0015867 0.0104892, -0.0602847 0.0043278 0.0127069 -0.0625489 0.0038938 0.0158233, -0.0637613 0.0006114 0.0174918 -0.0630086 -0.0030476 0.016456, -0.0595898 -0.0030476 0.0182122 -0.0599853 0.0006114 0.0194299, -0.0593482 0.0038938 0.0174684 -0.0581577 0.0043278 0.0138049, -0.0573106 0.0015867 0.0111979 -0.0574448 -0.0022655 0.0116106, -0.0584591 -0.0043279 0.0147323 0 -0.0043278 0.0151671, -0 -0.0022654 0.0118847 0 0.0015867 0.0114508, 0 0.0043279 0.0141919 0 0.0038938 0.018044, -0 0.0006115 0.0201063 -0 -0.0030475 0.018826
40 | ]
41 | }
42 | coordIndex [
43 | 76 63 69 -1 76 69 70 -1 70 69 68 -1 70 68 71 -1 71 68 67 -1 71 67 72 -1 72 67 73 -1 67 66 73 -1 73 66 74 -1 66 65 74 -1 74 65 75 -1 65 64 75 -1 75 64 63 -1 75 63 76 -1 64 61 63 -1 61 62 63 -1 65 60 61 -1 65 61 64 -1 66 59 60 -1 66 60 65 -1 67 58 59 -1 67 59 66 -1 68 57 67 -1 57 58 67 -1 69 56 68 -1 56 57 68 -1 63 62 69 -1 62 56 69 -1 62 49 56 -1 49 55 56 -1 56 55 57 -1 55 54 57 -1 57 54 58 -1 54 53 58 -1 58 53 52 -1 58 52 59 -1 59 52 51 -1 59 51 60 -1 60 51 50 -1 60 50 61 -1 61 50 62 -1 50 49 62 -1 50 47 49 -1 47 48 49 -1 51 46 47 -1 51 47 50 -1 52 45 46 -1 52 46 51 -1 53 44 45 -1 53 45 52 -1 54 43 53 -1 43 44 53 -1 55 42 54 -1 42 43 54 -1 49 48 55 -1 48 42 55 -1 48 35 42 -1 35 41 42 -1 42 41 43 -1 41 40 43 -1 43 40 44 -1 40 39 44 -1 44 39 38 -1 44 38 45 -1 45 38 37 -1 45 37 46 -1 46 37 36 -1 46 36 47 -1 47 36 48 -1 36 35 48 -1 22 21 33 -1 21 34 33 -1 23 22 33 -1 23 33 32 -1 24 23 32 -1 24 32 31 -1 25 24 31 -1 25 31 30 -1 26 25 29 -1 25 30 29 -1 27 26 28 -1 26 29 28 -1 21 27 34 -1 27 28 34 -1 20 14 21 -1 14 27 21 -1 14 15 27 -1 15 26 27 -1 15 16 26 -1 16 25 26 -1 16 17 24 -1 16 24 25 -1 17 18 23 -1 17 23 24 -1 18 19 22 -1 18 22 23 -1 19 20 22 -1 20 21 22 -1 8 7 19 -1 7 20 19 -1 9 8 19 -1 9 19 18 -1 10 9 18 -1 10 18 17 -1 11 10 17 -1 11 17 16 -1 12 11 15 -1 11 16 15 -1 13 12 14 -1 12 15 14 -1 7 13 20 -1 13 14 20 -1 6 0 7 -1 0 13 7 -1 0 1 13 -1 1 12 13 -1 1 2 12 -1 2 11 12 -1 2 3 10 -1 2 10 11 -1 3 4 9 -1 3 9 10 -1 4 5 8 -1 4 8 9 -1 5 6 8 -1 6 7 8 -1 75 76 6 -1 75 6 5 -1 74 75 4 -1 75 5 4 -1 73 74 3 -1 74 4 3 -1 72 73 2 -1 73 3 2 -1 71 72 2 -1 71 2 1 -1 1 0 70 -1 1 70 71 -1 0 6 76 -1 0 76 70 -1
44 | ]
45 | creaseAngle 1
46 | }
47 | }
48 | ]
49 | }
50 | DEF BODY_SHAPE Shape {
51 | appearance PBRAppearance {
52 | roughness 0.4
53 | metalness 0
54 | baseColorMap ImageTexture {
55 | url [
56 | "textures/body_3dx_base_color.jpg"
57 | ]
58 | }
59 | roughnessMap ImageTexture {
60 | url [
61 | "textures/body_3dx_roughness.jpg"
62 | ]
63 | }
64 | metalnessMap ImageTexture {
65 | url [
66 | "textures/body_3dx_metalness.jpg"
67 | ]
68 | }
69 | normalMap ImageTexture {
70 | url [
71 | "textures/body_3dx_normal.jpg"
72 | ]
73 | }
74 | occlusionMap ImageTexture {
75 | url [
76 | "textures/body_3dx_occlusion.jpg"
77 | ]
78 | }
79 | }
80 | geometry IndexedFaceSet {
81 | coord DEF coord_BODY_MESH Coordinate {
82 | point [
83 | -0.132024 0.0039377 -0.0942563, -0.100521 0.0039377 -0.131148 0.0994825 0.0039377 -0.131148, 0.130986 0.0039377 -0.0932017 0.130986 0.0039376 0.179241, -0.100521 0.0039377 0.211575 -0.132024 0.0039377 0.180296, -0.13189 -0.0297933 0.18015 -0.100387 -0.0297933 0.211429, 0.0996168 -0.0297933 0.211994 0.13112 -0.0297933 0.179095, 0.13112 -0.0297933 -0.0944398 0.0996169 -0.0297933 -0.131294, -0.100387 -0.0297932 -0.131294 -0.13189 -0.0297932 -0.0944025, -0.132024 0.139663 0.183523 -0.100521 0.139663 0.214802, 0.0994824 0.139663 0.214275 0.130986 0.139663 0.182468, 0.130986 0.139663 -0.0932017 0.0994825 0.139663 -0.131148, -0.100521 0.139663 -0.131148 -0.132024 0.139663 -0.0942563, -0.0752387 -0.0297933 0.211844 -0.0752387 -0.0297933 0.163759, 0.0743441 -0.0297933 0.163759 0.0743441 -0.0297933 0.211844, 0.0743441 0.0043409 0.211844 0.0743441 0.0043409 0.163759, -0.0752387 0.0043409 0.163759 -0.0752387 0.0043409 0.211844, 0.0996168 0.0043409 0.211994
84 | ]
85 | }
86 | texCoord TextureCoordinate {
87 | point [
88 | 0.958251 0.978885, 0.95748 0.97772, 0.95845 0.976487 0.957226 0.991457, 0.95579 0.983823, 0.966888 0.983203 0.966888 0.985547, 0.957226 0.991457, 0.966888 0.983203 0.958251 0.978885, 0.957401 0.978095, 0.95748 0.97772 0.961214 0.989698, 0.957226 0.991457, 0.966888 0.985547 0.956869 0.982813, 0.955772 0.983107, 0.955923 0.982862 0.95579 0.983823, 0.955772 0.983107, 0.956869 0.982813 0.957162 0.978238, 0.957269 0.978998, 0.956344 0.977674 0.955256 0.982709, 0.956176 0.982187, 0.955738 0.982688 0.95579 0.983823, 0.956869 0.982813, 0.966888 0.983203 0.966888 0.983203, 0.956869 0.982813, 0.958251 0.978885 0.95845 0.976487, 0.966888 0.983203, 0.958251 0.978885 0.956344 0.977674, 0.957269 0.978998, 0.956176 0.982187 0.956344 0.977674, 0.956176 0.982187, 0.955256 0.982709 0.955921 0.991618, 0.95497 0.983784, 0.95579 0.983823 0.955921 0.991618, 0.95579 0.983823, 0.957226 0.991457 0.29634 0.420164, 0.161286 0.420468, 0.163216 0.279933 0.29634 0.420164, 0.163216 0.279933, 0.29609 0.279548 0.536253 0.0534251, 0.536253 0.0445571, 0.821717 0.0445571 0.536253 0.0534251, 0.821717 0.0445571, 0.821717 0.0534251 0.710002 0.279936, 0.707963 0.42062, 0.29634 0.420164 0.710002 0.279936, 0.29634 0.420164, 0.29609 0.279548 0.95748 0.97772, 0.956344 0.977674, 0.941651 0.97201 0.95748 0.97772, 0.941651 0.97201, 0.95845 0.976487 0.95579 0.983823, 0.95497 0.983784, 0.955772 0.983107 0.95497 0.983784, 0.955256 0.982709, 0.955772 0.983107 0.841562 0.278905, 0.841721 0.420414, 0.707963 0.42062 0.841562 0.278905, 0.707963 0.42062, 0.710002 0.279936 0.958251 0.978885, 0.957269 0.978998, 0.957162 0.978238 0.958251 0.978885, 0.957162 0.978238, 0.957401 0.978095 0.955923 0.982862, 0.955738 0.982688, 0.956176 0.982187 0.955923 0.982862, 0.956176 0.982187, 0.956869 0.982813 0.956869 0.982813, 0.956176 0.982187, 0.957269 0.978998 0.956869 0.982813, 0.957269 0.978998, 0.958251 0.978885 0.957401 0.978095, 0.957162 0.978238, 0.956344 0.977674 0.957401 0.978095, 0.956344 0.977674, 0.95748 0.97772 0.955772 0.983107, 0.955256 0.982709, 0.955738 0.982688 0.955772 0.983107, 0.955738 0.982688, 0.955923 0.982862 0.933302 0.984685, 0.927875 0.980664, 0.927967 0.978408 0.933302 0.984685, 0.927967 0.978408, 0.950018 0.991525 0.952138 0.977899, 0.95265 0.982249, 0.950975 0.976534 0.95265 0.982249, 0.952195 0.98303, 0.950975 0.976534 0.952195 0.98303, 0.950018 0.991525, 0.927967 0.978408 0.952195 0.98303, 0.927967 0.978408, 0.950975 0.976534 0.707963 0.42062, 0.841721 0.420414, 0.841442 0.911609 0.707963 0.42062, 0.841442 0.911609, 0.707741 0.911923 0.161286 0.420468, 0.29634 0.420164, 0.296601 0.911901 0.161286 0.420468, 0.296601 0.911901, 0.161577 0.912051 0.955256 0.982709, 0.95497 0.983784, 0.952195 0.98303 0.955256 0.982709, 0.952195 0.98303, 0.95265 0.982249 0.941651 0.97201, 0.956344 0.977674, 0.950975 0.976534 0.956344 0.977674, 0.952138 0.977899, 0.950975 0.976534 0.956344 0.977674, 0.955256 0.982709, 0.952138 0.977899 0.955256 0.982709, 0.95265 0.982249, 0.952138 0.977899 0.29634 0.420164, 0.707963 0.42062, 0.707741 0.911923 0.29634 0.420164, 0.707741 0.911923, 0.296601 0.911901 0.95497 0.983784, 0.955921 0.991618, 0.950018 0.991525 0.95497 0.983784, 0.950018 0.991525, 0.952195 0.98303 0.536253 0.0534251, 0.821717 0.0534251, 0.536253 0.264946 0.821717 0.0534251, 0.821717 0.264946, 0.536253 0.264946
89 | ]
90 | }
91 | coordIndex [
92 | 24 8 7 -1 11 10 14 -1 13 11 14 -1 24 23 8 -1 12 11 13 -1 25 9 26 -1 10 9 25 -1 30 29 5 -1 31 28 27 -1 10 25 14 -1 14 25 24 -1 7 14 24 -1 5 29 28 -1 5 28 31 -1 3 4 10 -1 3 10 11 -1 2 3 11 -1 2 11 12 -1 0 14 7 -1 0 7 6 -1 13 1 2 -1 13 2 12 -1 8 5 6 -1 8 6 7 -1 10 4 9 -1 4 31 9 -1 14 0 1 -1 14 1 13 -1 24 29 30 -1 24 30 23 -1 26 27 28 -1 26 28 25 -1 25 28 29 -1 25 29 24 -1 23 30 5 -1 23 5 8 -1 9 31 27 -1 9 27 26 -1 20 21 22 -1 20 22 19 -1 16 17 15 -1 17 18 15 -1 18 19 22 -1 18 22 15 -1 1 0 22 -1 1 22 21 -1 3 2 20 -1 3 20 19 -1 31 4 18 -1 31 18 17 -1 6 5 15 -1 5 16 15 -1 5 31 16 -1 31 17 16 -1 2 1 21 -1 2 21 20 -1 4 3 19 -1 4 19 18 -1 0 6 22 -1 6 15 22 -1
93 | ]
94 | texCoordIndex [
95 | 0 1 2 -1 3 4 5 -1 6 7 8 -1 9 10 11 -1 12 13 14 -1 15 16 17 -1 18 19 20 -1 21 22 23 -1 24 25 26 -1 27 28 29 -1 30 31 32 -1 33 34 35 -1 36 37 38 -1 39 40 41 -1 42 43 44 -1 45 46 47 -1 48 49 50 -1 51 52 53 -1 54 55 56 -1 57 58 59 -1 60 61 62 -1 63 64 65 -1 66 67 68 -1 69 70 71 -1 72 73 74 -1 75 76 77 -1 78 79 80 -1 81 82 83 -1 84 85 86 -1 87 88 89 -1 90 91 92 -1 93 94 95 -1 96 97 98 -1 99 100 101 -1 102 103 104 -1 105 106 107 -1 108 109 110 -1 111 112 113 -1 114 115 116 -1 117 118 119 -1 120 121 122 -1 123 124 125 -1 126 127 128 -1 129 130 131 -1 132 133 134 -1 135 136 137 -1 138 139 140 -1 141 142 143 -1 144 145 146 -1 147 148 149 -1 150 151 152 -1 153 154 155 -1 156 157 158 -1 159 160 161 -1 162 163 164 -1 165 166 167 -1 168 169 170 -1 171 172 173 -1 174 175 176 -1 177 178 179 -1
96 | ]
97 | }
98 | }
99 | DEF BLACK_BUTTON_1 Transform {
100 | translation -0.136649 0.0705678 0.0538892
101 | rotation 1 0 0 0
102 | children [
103 | DEF BLACK_BUTTON_SHAPE Shape {
104 | appearance PBRAppearance {
105 | metalness 0
106 | baseColor 0 0 0
107 | roughness 0.3
108 | }
109 | geometry IndexedFaceSet {
110 | coord DEF coord_BLACK_BUTTON Coordinate {
111 | point [
112 | -0.0045 -0.003186 -0.003182, -0.0045 -0.0044975 0 -0.0045 -0.003186 0.0031819, -0.0045 0 0.0045 -0.0045 0.0031792 0.0031819, -0.0045 0.0044975 0 -0.0045 0.0031792 -0.003182, -0.0045 0 -0.0045 0.0045 -0.003186 -0.003182, 0.0045 -0.0044975 0 0.0045 -0.003186 0.0031819, 0.0045 0 0.0045 0.0045 0.0031792 0.0031819, 0.0045 0.0044975 0 0.0045 0.0031792 -0.003182, 0.0045 0 -0.0045 -0.0045 0 0, 0.0045 0 0
113 | ]
114 | }
115 | coordIndex [
116 | 16 0 1 -1 17 9 8 -1 16 1 2 -1 17 10 9 -1 16 2 3 -1 17 11 10 -1 16 3 4 -1 17 12 11 -1 16 4 5 -1 17 13 12 -1 16 5 6 -1 17 14 13 -1 16 6 7 -1 17 15 14 -1 7 0 16 -1 17 8 15 -1 8 0 7 -1 8 7 15 -1 6 14 15 -1 6 15 7 -1 5 13 14 -1 5 14 6 -1 4 12 13 -1 4 13 5 -1 3 11 12 -1 3 12 4 -1 2 10 11 -1 2 11 3 -1 1 9 10 -1 1 10 2 -1 0 8 9 -1 0 9 1 -1
117 | ]
118 | creaseAngle 1.5
119 | }
120 | }
121 | ]
122 | }
123 | DEF BLACK_BUTTON_2 Transform {
124 | translation -0.137079 0.0706655 0.0641166
125 | rotation 1 0 0 0
126 | children [
127 | USE BLACK_BUTTON_SHAPE
128 | ]
129 | }
130 | DEF FRONT_BLACK_PANEL Transform {
131 | translation 0.0332066 -0.0130239 -0.131036
132 | rotation 1 0 0 0
133 | children [
134 | DEF FRONT_BLACK_PANEL_SHAPE Shape {
135 | appearance PBRAppearance {
136 | baseColor 0.06 0.06 0.06
137 | metalness 0
138 | roughness 0.2
139 | }
140 | geometry IndexedFaceSet {
141 | coord DEF coord_frontBlackPanelMesh Coordinate {
142 | point [
143 | -0.030608 -0.0145753 -0.0028225, 0.0301916 -0.0145753 -0.0028225 0.030608 0.0145753 -0.0028225, -0.030608 0.0145753 -0.0028225 -0.030608 0.0145753 0.0028225, 0.030608 0.0145753 0.0028225 0.0301916 -0.0145753 0.0028225, -0.030608 -0.0145753 0.0028225
144 | ]
145 | }
146 | coordIndex [
147 | 5 4 6 -1 4 7 6 -1 7 0 1 -1 7 1 6 -1 2 5 6 -1 2 6 1 -1 3 4 5 -1 3 5 2 -1 0 7 4 -1 0 4 3 -1 0 3 1 -1 3 2 1 -1
148 | ]
149 | creaseAngle 1
150 | }
151 | }
152 | ]
153 | }
154 | DEF JOINT Transform {
155 | translation 0.0005795 0.0027087 0.191364
156 | rotation 1 0 0 0
157 | children [
158 | DEF JOINT_SHAPE Shape {
159 | appearance PBRAppearance {
160 | metalness 0
161 | baseColor 0.8 0.8 0.8
162 | }
163 | geometry IndexedFaceSet {
164 | coord DEF coord_JOINT_MESH Coordinate {
165 | point [
166 | -0.0458395 0.0011984 -0.0199851, 0.0456398 0.0011984 -0.0199851 0.0458395 -0.0011984 -0.0199851, -0.0458395 -0.0011984 -0.0199851 -0.0458395 -0.0011984 0.0199851, 0.0458395 -0.0011984 0.0199851 0.0456398 0.0011984 0.0199851, -0.0458395 0.0011984 0.0199851
167 | ]
168 | }
169 | coordIndex [
170 | 4 5 6 -1 4 6 7 -1 0 7 6 -1 0 6 1 -1 1 6 5 -1 1 5 2 -1 2 5 4 -1 2 4 3 -1 7 0 3 -1 7 3 4 -1 3 0 1 -1 3 1 2 -1
171 | ]
172 | creaseAngle 1
173 | }
174 | }
175 | ]
176 | }
177 | DEF LEFT_AXLE Transform {
178 | translation -0.136 -0 -0
179 | rotation 1 0 0 0
180 | children [
181 | DEF LEFT_AXLE_SHAPE Shape {
182 | appearance PBRAppearance {
183 | baseColor 0.8 0.8 0.8
184 | roughness 0.3
185 | }
186 | geometry IndexedFaceSet {
187 | coord DEF coord_LEFT_AXLE Coordinate {
188 | point [
189 | -0.0055745 -0.0193486 -0.0193476, -0.0055745 -0.027025 -0.0042792 -0.0055745 -0.0243805 0.01242, -0.0055745 -0.0124236 0.0243782 -0.0055745 0.0042782 0.027024, -0.0055745 0.019344 0.0193476 -0.0055745 0.0270205 0.0042792, -0.0055745 0.024376 -0.01242 -0.0055745 0.0124191 -0.0243782, -0.0055745 -0.0042827 -0.027024 0.0055764 -0.0193486 -0.0193476, 0.0055764 -0.027025 -0.0042792 0.0055764 -0.0243805 0.01242, 0.0055764 -0.0124236 0.0243782 0.0055764 0.0042782 0.027024, 0.0055764 0.019344 0.0193476 0.0055764 0.0270205 0.0042792, 0.0055764 0.024376 -0.01242 0.0055764 0.0124191 -0.0243782, 0.0055764 -0.0042827 -0.027024
190 | ]
191 | }
192 | coordIndex [
193 | 10 0 9 -1 10 9 19 -1 8 18 19 -1 8 19 9 -1 7 17 18 -1 7 18 8 -1 6 16 17 -1 6 17 7 -1 5 15 16 -1 5 16 6 -1 4 14 15 -1 4 15 5 -1 3 13 14 -1 3 14 4 -1 2 12 13 -1 2 13 3 -1 1 11 12 -1 1 12 2 -1 0 10 11 -1 0 11 1 -1 7 5 6 -1 8 5 7 -1 8 4 5 -1 9 4 8 -1 9 3 4 -1 0 3 9 -1 0 2 3 -1 2 0 1 -1
194 | ]
195 | creaseAngle 1
196 | }
197 | }
198 | ]
199 | }
200 | DEF ON_BUTTON Transform {
201 | translation -0.131799 0.0706764 0.155313
202 | rotation 1 0 0 0
203 | children [
204 | Shape {
205 | appearance PBRAppearance {
206 | baseColor 0 0 0
207 | metalness 0
208 | roughness 0.3
209 | }
210 | geometry IndexedFaceSet {
211 | coord DEF coord_onButtonMesh Coordinate {
212 | point [
213 | -0.0016436 0.0021051 0.002947, -0.0016436 0.0021051 -0.0029468 -0.0016436 -0.0021051 -0.002947, -0.0016436 -0.0020828 0.002947 0.0016435 -0.0020828 0.002947, 0.0016435 -0.0021051 -0.002947 0.0016435 0.0021051 -0.0029468, 0.0016435 0.0021051 0.002947
214 | ]
215 | }
216 | coordIndex [
217 | 5 6 4 -1 6 7 4 -1 1 0 7 -1 1 7 6 -1 2 1 6 -1 2 6 5 -1 3 2 5 -1 3 5 4 -1 0 3 4 -1 0 4 7 -1 0 1 3 -1 1 2 3 -1
218 | ]
219 | creaseAngle 1
220 | }
221 | }
222 | ]
223 | }
224 | DEF RED_BUTTON Transform {
225 | translation -0.136623 0.0706176 0.0821193
226 | rotation 1 0 0 0
227 | children [
228 | Shape {
229 | appearance PBRAppearance {
230 | baseColor 1 0 0
231 | metalness 0
232 | roughness 0.3
233 | }
234 | geometry IndexedFaceSet {
235 | coord Coordinate {
236 | point [
237 | -0.0045 -0.003182 -0.003182, -0.0045 -0.0045 0 -0.0045 -0.003182 0.003182, -0.0045 0 0.0045 -0.0045 0.003182 0.003182, -0.0045 0.0045 -0 -0.0045 0.003182 -0.003182, -0.0045 0 -0.0045 0.0045 -0.003182 -0.003182, 0.0045 -0.0045 -0 0.0045 -0.003182 0.003182, 0.0045 0 0.0045 0.0045 0.003182 0.003182, 0.0045 0.0045 -0 0.0045 0.003182 -0.003182, 0.0045 -0 -0.0045 -0.0045 -0 0, 0.0045 0 0
238 | ]
239 | }
240 | coordIndex [
241 | 16 0 1 -1 17 9 8 -1 16 1 2 -1 17 10 9 -1 16 2 3 -1 17 11 10 -1 16 3 4 -1 17 12 11 -1 16 4 5 -1 17 13 12 -1 16 5 6 -1 17 14 13 -1 16 6 7 -1 17 15 14 -1 7 0 16 -1 17 8 15 -1 8 0 7 -1 8 7 15 -1 6 14 15 -1 6 15 7 -1 5 13 14 -1 5 14 6 -1 4 12 13 -1 4 13 5 -1 3 11 12 -1 3 12 4 -1 2 10 11 -1 2 11 3 -1 1 9 10 -1 1 10 2 -1 0 8 9 -1 0 9 1 -1
242 | ]
243 | creaseAngle 1.5
244 | }
245 | }
246 | ]
247 | }
248 | DEF RIGHT_AXLE Transform {
249 | translation 0.136317 -0.0001156 0
250 | rotation 1 0 0 0
251 | children [
252 | DEF RIGHT_AXLE_SHAPE Shape {
253 | appearance PBRAppearance {
254 | baseColor 0.8 0.8 0.8
255 | roughness 0.3
256 | }
257 | geometry IndexedFaceSet {
258 | coord DEF coord_RIGHT_AXLE Coordinate {
259 | point [
260 | -0.0055745 -0.0193486 -0.0193476, -0.0055745 -0.027025 -0.0042792 -0.0055745 -0.0243805 0.01242, -0.0055745 -0.0124236 0.0243782 -0.0055745 0.0042782 0.027024, -0.0055745 0.019344 0.0193476 -0.0055745 0.0270205 0.0042792, -0.0055745 0.024376 -0.01242 -0.0055745 0.0124191 -0.0243782, -0.0055745 -0.0042827 -0.027024 0.0055764 -0.0193486 -0.0193476, 0.0055764 -0.027025 -0.0042792 0.0055764 -0.0243805 0.01242, 0.0055764 -0.0124236 0.0243782 0.0055764 0.0042782 0.027024, 0.0055764 0.019344 0.0193476 0.0055764 0.0270205 0.0042792, 0.0055764 0.024376 -0.01242 0.0055764 0.0124191 -0.0243782, 0.0055764 -0.0042827 -0.027024
261 | ]
262 | }
263 | coordIndex [
264 | 10 0 9 -1 10 9 19 -1 8 18 19 -1 8 19 9 -1 7 17 18 -1 7 18 8 -1 6 16 17 -1 6 17 7 -1 5 15 16 -1 5 16 6 -1 4 14 15 -1 4 15 5 -1 3 13 14 -1 3 14 4 -1 2 12 13 -1 2 13 3 -1 1 11 12 -1 1 12 2 -1 0 10 11 -1 0 11 1 -1 17 16 15 -1 18 17 15 -1 18 15 14 -1 19 18 14 -1 19 14 13 -1 10 19 13 -1 10 13 12 -1 11 10 12 -1
265 | ]
266 | creaseAngle 1
267 | }
268 | }
269 | ]
270 | }
271 | DEF SERIAL_PLUG Transform {
272 | translation -0.132219 0.0987955 0.0633308
273 | rotation 1 0 0 0
274 | children [
275 | Shape {
276 | appearance PBRAppearance {
277 | metalness 0
278 | roughness 1
279 | baseColorMap ImageTexture {
280 | url [
281 | "textures/serial_plug.jpg"
282 | ]
283 | }
284 | }
285 | geometry IndexedFaceSet {
286 | coord DEF coord_serialPlugMesh Coordinate {
287 | point [
288 | -0.0014489 0.0070379 0.0033234, -0.0014489 0.007415 0.0023195 -0.0014489 0.0066469 -0.0033234, -0.0014489 -0.0065165 -0.0033234 -0.0014489 -0.0072985 0.0033234, 0.0020108 -0.0072985 0.0033234 0.0020108 -0.0065165 -0.0033234, 0.0020108 0.0066469 -0.0033234 0.0020108 0.007415 0.0023195, 0.0020108 0.0070379 0.0033234
289 | ]
290 | }
291 | texCoord TextureCoordinate {
292 | point [
293 | 0.0229907 0.99073, 0.0076335 0.506001, 0.0728771 0.0331792 0.191839 0.0560876, 0.176237 0.0560876, 0.180345 0.0487028 0.191839 0.0560876, 0.176237 0.0560876, 0.180345 0.0487028 0.191839 0.0560876, 0.176237 0.0560876, 0.180345 0.0487028 0.191839 0.0560876, 0.176237 0.0560876, 0.180345 0.0487028 0.191839 0.0560876, 0.176237 0.0560876, 0.180345 0.0487028 0.191839 0.0560876, 0.176237 0.0560876, 0.180345 0.0487028 0.191839 0.0560876, 0.176237 0.0560876, 0.180345 0.0487028 0.191839 0.0560876, 0.176237 0.0560876, 0.180345 0.0487028 0.191839 0.0560876, 0.176237 0.0560876, 0.180345 0.0487028 0.191839 0.0560876, 0.176237 0.0560876, 0.180345 0.0487028 0.0229907 0.99073, 0.0728771 0.0331792, 0.948102 0.033179 0.0229907 0.99073, 0.948102 0.033179, 0.971915 0.992965
294 | ]
295 | }
296 | coordIndex [
297 | 0 1 2 -1 1 0 9 -1 1 9 8 -1 2 1 8 -1 2 8 7 -1 3 2 7 -1 3 7 6 -1 4 3 6 -1 4 6 5 -1 0 4 5 -1 0 5 9 -1 0 2 3 -1 0 3 4 -1
298 | ]
299 | texCoordIndex [
300 | 0 1 2 -1 3 4 5 -1 6 7 8 -1 9 10 11 -1 12 13 14 -1 15 16 17 -1 18 19 20 -1 21 22 23 -1 24 25 26 -1 27 28 29 -1 30 31 32 -1 33 34 35 -1 36 37 38 -1
301 | ]
302 | }
303 | }
304 | ]
305 | }
306 | DEF SONAR_RING Transform {
307 | translation -0.0011084 0.114168 0.0468148
308 | rotation 1 0 0 0
309 | children [
310 | DEF SONAR_RING_SHAPE Shape {
311 | appearance PBRAppearance {
312 | baseColor 1 0 0
313 | metalness 0
314 | roughness 0.4
315 | }
316 | geometry IndexedFaceSet {
317 | coord DEF coord_SONAR_RING Coordinate {
318 | point [
319 | 0.139202 0.026895 -0.0799306, 0.139202 0.026895 -0.135788 0.103298 0.026895 -0.178418, 0.0549782 0.0268949 -0.206197 3.12e-05 0.0268949 -0.215774, -0.0548752 0.0268949 -0.206197 -0.103195 0.0268949 -0.178418, -0.139099 0.0268949 -0.135788 -0.139099 0.0268949 -0.0799307, 0.139202 -0.0262469 -0.135788 0.103298 -0.0262469 -0.178418, 0.139202 -0.0262468 -0.0799306 0.0549782 -0.0262469 -0.206197, 3.12e-05 -0.0262469 -0.215774 -0.0548752 -0.0262469 -0.206197, -0.103195 -0.0262469 -0.178418 -0.139099 -0.0262469 -0.135788, -0.139099 -0.0262469 -0.0799307 -0.139202 -0.026895 0.0802712, -0.139202 -0.026895 0.135989 -0.103388 -0.0268949 0.178512, -0.0551892 -0.0268949 0.206221 -0.0004203 -0.0268949 0.215774, 0.0543892 -0.0268949 0.206221 0.138402 -0.0268949 0.0802711, 0.102588 -0.0268949 0.178511 0.138402 -0.0268949 0.135989, -0.139202 0.0262323 0.0802712 -0.139202 0.0262323 0.135989, -0.103388 0.0262323 0.178512 -0.0551892 0.0262323 0.206221, -0.0004203 0.0262323 0.215774 0.0543892 0.0262323 0.206221, 0.102588 0.0262324 0.178511 0.138402 0.0262324 0.135989, 0.138402 0.0262324 0.0802711
320 | ]
321 | }
322 | coordIndex [
323 | 0 4 8 -1 0 2 4 -1 4 6 8 -1 6 7 8 -1 4 5 6 -1 2 3 4 -1 0 1 2 -1 10 9 11 -1 13 12 10 -1 15 14 13 -1 17 16 15 -1 17 15 13 -1 13 10 11 -1 17 13 11 -1 18 24 22 -1 22 24 25 -1 18 22 20 -1 18 20 19 -1 20 22 21 -1 22 25 23 -1 25 24 26 -1 35 33 34 -1 33 31 32 -1 31 29 30 -1 29 27 28 -1 31 27 29 -1 35 31 33 -1 35 27 31 -1 33 25 26 -1 33 26 34 -1 34 26 24 -1 34 24 35 -1 31 22 23 -1 31 23 32 -1 32 23 25 -1 32 25 33 -1 29 20 21 -1 29 21 30 -1 30 21 22 -1 30 22 31 -1 27 18 19 -1 27 19 28 -1 28 19 20 -1 28 20 29 -1 35 24 18 -1 35 18 27 -1 0 8 17 -1 0 17 11 -1 7 6 15 -1 7 15 16 -1 8 7 16 -1 8 16 17 -1 5 4 13 -1 5 13 14 -1 6 5 14 -1 6 14 15 -1 3 2 10 -1 3 10 12 -1 4 3 12 -1 4 12 13 -1 1 0 11 -1 1 11 9 -1 2 1 9 -1 2 9 10 -1
324 | ]
325 | }
326 | }
327 | ]
328 | }
329 | DEF TOP Transform {
330 | translation -0.0014845 0.143314 0.0448051
331 | rotation 1 0 0 0
332 | children [
333 | DEF upperBlackPanel Transform {
334 | translation 0.0008437 0.0036847 -0.0355538
335 | rotation 1 0 0 0
336 | children [
337 | Shape {
338 | appearance PBRAppearance {
339 | baseColor 0.2 0.2 0.2
340 | metalness 0
341 | roughness 0.3
342 | }
343 | geometry IndexedFaceSet {
344 | coord DEF coord_upperBlackPanelMesh Coordinate {
345 | point [
346 | -0.0316485 0 -0.0158242, 0.0316485 0 -0.0150882 0.0316485 0 0.0158242, -0.0316485 0 0.0158242 -0.0316485 -0.0018164 0.0158242, 0.0316485 -0.0018164 0.0158242 0.0316485 -0.0018164 -0.0150882, -0.0316485 -0.0018164 -0.0158242
347 | ]
348 | }
349 | coordIndex [
350 | 5 4 6 -1 4 7 6 -1 7 0 1 -1 7 1 6 -1 2 5 6 -1 2 6 1 -1 3 4 5 -1 3 5 2 -1 0 7 4 -1 0 4 3 -1 0 3 1 -1 3 2 1 -1
351 | ]
352 | creaseAngle 1
353 | }
354 | }
355 | ]
356 | }
357 | DEF TOP_SHAPE Shape {
358 | appearance PBRAppearance {
359 | roughness 0.25
360 | metalness 0
361 | baseColorMap ImageTexture {
362 | url [
363 | "textures/top_3dx_base_color.jpg"
364 | ]
365 | }
366 | normalMap ImageTexture {
367 | url [
368 | "textures/top_3dx_normal.jpg"
369 | ]
370 | }
371 | normalMapFactor 0.1
372 | }
373 | geometry IndexedFaceSet {
374 | coord Coordinate {
375 | point [
376 | -0.0459787 -0.0030734 0.216208, -0.0923722 -0.0030734 0.198787 -0.141055 -0.0030734 0.168074, -0.161757 -0.0030734 0.146229 -0.162382 -0.0030734 0.0619703, -0.167375 -0.0030734 0.0457426 -0.189987 -0.0030734 0.0236839, -0.189915 -0.0030734 -0.112765 -0.161286 -0.0030734 -0.150119, -0.134877 -0.0030734 -0.174107 -0.094308 -0.0030734 -0.199395, -0.0491816 -0.0030734 -0.214916 -0.156363 -0.0030734 0.0746773, -0.156363 -0.0030734 0.0292581 -0.136558 -0.0030734 0.0304034, -0.136558 -0.0030734 0.0751422 -0.138973 -0.0030734 0.081582, -0.147023 -0.0030734 0.0839969 -0.154753 -0.0030734 0.080777, -0.139778 -0.0030734 0.0255735 -0.146558 -0.0030734 0.0212084, -0.153484 -0.0030734 0.0244283 0.155499 -0.0030734 0.0229441, 0.149864 -0.0030734 0.0197242 0.143084 -0.0030734 0.0240893, 0.156768 -0.0030734 0.0792929 0.150329 -0.0030734 0.0825128, 0.142279 -0.0030734 0.0800979 0.139864 -0.0030734 0.073658, 0.139864 -0.0030734 0.0289192 0.158378 -0.0030734 0.027774, 0.158379 -0.0030734 0.0731932 -0.000623 -0.0030734 0.219407, -0.0003324 -0.0030734 -0.221384 0.0532294 -0.0030734 -0.214916, 0.0983558 -0.0030734 -0.198653 0.138183 -0.0030734 -0.174107, 0.161817 -0.0030734 -0.152346 0.189987 -0.0030734 -0.114897, 0.188114 -0.0030734 0.0241435 0.16939 -0.0030734 0.0442585, 0.164397 -0.0030734 0.0604862 0.163772 -0.0030734 0.144745, 0.142715 -0.0030734 0.16659 0.0914508 -0.0030734 0.199103, 0.0500261 -0.0030734 0.216208 0.0500261 0.0019175 0.216208, 0.0914508 0.0019175 0.199103 0.142715 0.0019175 0.16659, 0.163772 0.0019175 0.144745 0.164397 0.0019175 0.0604862, 0.16939 0.0019175 0.0442585 0.188114 0.0019175 0.0241435, 0.189987 0.0019175 -0.114897 0.161817 0.0019175 -0.152346, 0.138183 0.0019175 -0.174107 0.0983558 0.0019175 -0.198653, 0.0532294 0.0019175 -0.214916 -0.0003324 0.0019175 -0.221384, -0.000623 0.0019175 0.219407 0.158379 0.0019175 0.0731932, 0.158378 0.0019175 0.027774 0.139864 0.0019175 0.0289192, 0.139864 0.0019175 0.073658 0.142279 0.0019175 0.0800979, 0.150329 0.0019175 0.0825128 0.156768 0.0019175 0.0792929, 0.143084 0.0019175 0.0240893 0.149864 0.0019175 0.0197242, 0.155499 0.0019175 0.0229441 -0.153484 0.0019175 0.0244283, -0.146558 0.0019175 0.0212084 -0.139778 0.0019175 0.0255735, -0.154753 0.0019175 0.080777 -0.147023 0.0019175 0.0839969, -0.138973 0.0019175 0.081582 -0.136558 0.0019175 0.0751422, -0.136558 0.0019175 0.0304034 -0.156363 0.0019175 0.0292581, -0.156363 0.0019175 0.0746773 -0.0491816 0.0019175 -0.214916, -0.094308 0.0019175 -0.199395 -0.134877 0.0019175 -0.174107, -0.161286 0.0019175 -0.150119 -0.189915 0.0019175 -0.112765, -0.189987 0.0019175 0.0236839 -0.167375 0.0019175 0.0457426, -0.162382 0.0019175 0.0619703 -0.161757 0.0019175 0.146229, -0.141055 0.0019175 0.168074 -0.0923722 0.0019175 0.198787, -0.0459787 0.0019175 0.216208
377 | ]
378 | }
379 | texCoord TextureCoordinate {
380 | point [
381 | 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.11307 0.307198, 0.092725 0.314503, 0.074292 0.166015 0.89563 0.310565, 0.931011 0.169381, 0.912578 0.317869 0.499125 1, 0.132136 0.43974, 0.876563 0.443107 0.0884878 0.431381, 0 0.444027, 0.0595085 0.393983 0.0960666 0.442338, 0.251803 0.950116, 0.145035 0.892745 0.998323 0.442984, 0.916815 0.434748, 0.945794 0.39735 0.640087 0.985327, 0.894407 0.45301, 0.75885 0.948432 0.49836 0, 0.631657 0.0072576, 0.378995 0.0072577 0.134255 0.312676, 0.11307 0.307198, 0.074292 0.166015 0.931011 0.169381, 0.89563 0.310565, 0.874444 0.316043 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.932653 0.360535, 0.945794 0.39735, 0.916815 0.331707 0.945794 0.39735, 0.916815 0.434748, 0.916815 0.331707 0.740677 0.0460614, 0.875592 0.119823, 0.128776 0.116456 0.740677 0.0460614, 0.128776 0.116456, 0.256898 0.0467791 0.256898 0.0467791, 0.378995 0.0072577, 0.740677 0.0460614 0.378995 0.0072577, 0.631657 0.0072576, 0.740677 0.0460614 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.874444 0.316043, 0.868089 0.330653, 0.140611 0.327286 0.874444 0.316043, 0.140611 0.327286, 0.134255 0.312676 0.931011 0.169381, 0.874444 0.316043, 0.134255 0.312676 0.931011 0.169381, 0.134255 0.312676, 0.074292 0.166015 0.931011 0.169381, 0.074292 0.166015, 0.875592 0.119823 0.074292 0.166015, 0.128776 0.116456, 0.875592 0.119823 0.75885 0.948432, 0.894407 0.45301, 0.863665 0.892744 0.894407 0.45301, 0.909236 0.445705, 0.863665 0.892744 0.925863 0.843376, 0.863665 0.892744, 0.909236 0.445705 0.925863 0.843376, 0.909236 0.445705, 0.916815 0.434748 0.499125 1, 0.876563 0.443107, 0.640087 0.985327 0.876563 0.443107, 0.894407 0.45301, 0.640087 0.985327 0.998323 0.442984, 1 0.758419, 0.916815 0.434748 1 0.758419, 0.925863 0.843376, 0.916815 0.434748 0.0755341 0.838326, 0.0001881 0.753582, 0.0884878 0.431381 0.0001881 0.753582, 0 0.444027, 0.0884878 0.431381 0.0960666 0.442338, 0.145035 0.892745, 0.0755341 0.838326 0.0960666 0.442338, 0.0755341 0.838326, 0.0884878 0.431381 0.114293 0.449643, 0.370565 0.985327, 0.251803 0.950116 0.114293 0.449643, 0.251803 0.950116, 0.0960666 0.442338 0.132136 0.43974, 0.499125 1, 0.370565 0.985327 0.132136 0.43974, 0.370565 0.985327, 0.114293 0.449643 0.868089 0.330653, 0.868089 0.43215, 0.140611 0.428783 0.868089 0.330653, 0.140611 0.428783, 0.140611 0.327286 0.876563 0.443107, 0.132136 0.43974, 0.868089 0.43215 0.132136 0.43974, 0.140611 0.428783, 0.868089 0.43215 0.916815 0.331707, 0.912578 0.317869, 0.932653 0.360535 0.912578 0.317869, 0.931011 0.169381, 0.932653 0.360535 0.0884878 0.328341, 0.0726494 0.357168, 0.092725 0.314503 0.0726494 0.357168, 0.074292 0.166015, 0.092725 0.314503 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.0884878 0.431381, 0.0595085 0.393983, 0.0726494 0.357168 0.0884878 0.431381, 0.0726494 0.357168, 0.0884878 0.328341 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834 0.400446 0.698048, 0.574232 0.698048, 0.574232 0.871834
382 | ]
383 | }
384 | coordIndex [
385 | 19 33 24 -1 5 6 13 -1 9 10 21 -1 30 39 40 -1 23 34 35 -1 3 17 16 -1 26 42 27 -1 74 73 88 -1 65 49 66 -1 58 72 67 -1 78 85 86 -1 70 81 82 -1 52 61 51 -1 57 68 56 -1 59 46 91 -1 75 74 88 -1 49 65 64 -1 31 30 40 -1 31 40 41 -1 50 51 60 -1 51 61 60 -1 47 48 89 -1 47 89 90 -1 90 91 47 -1 91 46 47 -1 0 91 90 -1 0 90 1 -1 44 47 46 -1 44 46 45 -1 32 45 46 -1 32 46 59 -1 0 32 59 -1 0 59 91 -1 64 63 76 -1 64 76 75 -1 49 64 75 -1 49 75 88 -1 49 88 48 -1 88 89 48 -1 56 68 55 -1 68 69 55 -1 54 55 69 -1 54 69 61 -1 58 67 57 -1 67 68 57 -1 52 53 61 -1 53 54 61 -1 83 84 78 -1 84 85 78 -1 70 82 83 -1 70 83 78 -1 71 80 81 -1 71 81 70 -1 72 58 80 -1 72 80 71 -1 63 62 77 -1 63 77 76 -1 67 72 62 -1 72 77 62 -1 60 66 50 -1 66 49 50 -1 79 87 73 -1 87 88 73 -1 2 1 90 -1 2 90 89 -1 4 3 88 -1 4 88 87 -1 5 4 87 -1 5 87 86 -1 6 5 86 -1 6 86 85 -1 7 6 85 -1 7 85 84 -1 8 7 84 -1 8 84 83 -1 9 8 83 -1 9 83 82 -1 10 9 82 -1 10 82 81 -1 10 81 80 -1 10 80 11 -1 12 13 78 -1 12 78 79 -1 15 76 77 -1 15 77 14 -1 16 75 76 -1 16 76 15 -1 16 17 74 -1 16 74 75 -1 17 18 73 -1 17 73 74 -1 19 72 71 -1 19 71 20 -1 20 71 70 -1 20 70 21 -1 18 12 79 -1 18 79 73 -1 14 77 72 -1 14 72 19 -1 13 21 70 -1 13 70 78 -1 30 61 69 -1 30 69 22 -1 24 67 62 -1 24 62 29 -1 25 66 60 -1 25 60 31 -1 22 69 68 -1 22 68 23 -1 23 68 67 -1 23 67 24 -1 26 65 66 -1 26 66 25 -1 27 64 65 -1 27 65 26 -1 28 63 64 -1 28 64 27 -1 29 62 63 -1 29 63 28 -1 31 60 61 -1 31 61 30 -1 33 58 57 -1 33 57 34 -1 34 57 56 -1 34 56 35 -1 35 56 55 -1 35 55 36 -1 36 55 54 -1 36 54 37 -1 37 54 53 -1 37 53 38 -1 38 53 52 -1 38 52 39 -1 39 52 51 -1 39 51 40 -1 40 51 50 -1 40 50 41 -1 41 50 49 -1 41 49 42 -1 44 43 48 -1 44 48 47 -1 11 80 58 -1 11 58 33 -1 3 2 89 -1 3 89 88 -1 43 42 49 -1 43 49 48 -1 15 28 27 -1 15 27 16 -1 16 27 42 -1 16 42 3 -1 0 1 44 -1 1 2 44 -1 2 43 44 -1 2 3 43 -1 3 42 43 -1 22 23 36 -1 23 35 36 -1 22 36 37 -1 22 37 30 -1 23 24 34 -1 24 33 34 -1 37 38 30 -1 38 39 30 -1 6 7 13 -1 7 8 13 -1 8 9 21 -1 8 21 13 -1 10 11 20 -1 10 20 21 -1 11 33 19 -1 11 19 20 -1 14 29 28 -1 14 28 15 -1 14 19 29 -1 19 24 29 -1 42 25 41 -1 25 31 41 -1 3 4 18 -1 4 12 18 -1 13 4 5 -1 13 12 4 -1 78 86 87 -1 78 87 79 -1 3 18 17 -1 25 42 26 -1 32 44 45 -1 0 44 32 -1
386 | ]
387 | texCoordIndex [
388 | 0 1 2 -1 3 4 5 -1 6 7 8 -1 9 10 11 -1 12 13 14 -1 15 16 17 -1 18 19 20 -1 21 22 23 -1 24 25 26 -1 27 28 29 -1 30 31 32 -1 33 34 35 -1 36 37 38 -1 39 40 41 -1 42 43 44 -1 45 46 47 -1 48 49 50 -1 51 52 53 -1 54 55 56 -1 57 58 59 -1 60 61 62 -1 63 64 65 -1 66 67 68 -1 69 70 71 -1 72 73 74 -1 75 76 77 -1 78 79 80 -1 81 82 83 -1 84 85 86 -1 87 88 89 -1 90 91 92 -1 93 94 95 -1 96 97 98 -1 99 100 101 -1 102 103 104 -1 105 106 107 -1 108 109 110 -1 111 112 113 -1 114 115 116 -1 117 118 119 -1 120 121 122 -1 123 124 125 -1 126 127 128 -1 129 130 131 -1 132 133 134 -1 135 136 137 -1 138 139 140 -1 141 142 143 -1 144 145 146 -1 147 148 149 -1 150 151 152 -1 153 154 155 -1 156 157 158 -1 159 160 161 -1 162 163 164 -1 165 166 167 -1 168 169 170 -1 171 172 173 -1 174 175 176 -1 177 178 179 -1 180 181 182 -1 183 184 185 -1 186 187 188 -1 189 190 191 -1 192 193 194 -1 195 196 197 -1 198 199 200 -1 201 202 203 -1 204 205 206 -1 207 208 209 -1 210 211 212 -1 213 214 215 -1 216 217 218 -1 219 220 221 -1 222 223 224 -1 225 226 227 -1 228 229 230 -1 231 232 233 -1 234 235 236 -1 237 238 239 -1 240 241 242 -1 243 244 245 -1 246 247 248 -1 249 250 251 -1 252 253 254 -1 255 256 257 -1 258 259 260 -1 261 262 263 -1 264 265 266 -1 267 268 269 -1 270 271 272 -1 273 274 275 -1 276 277 278 -1 279 280 281 -1 282 283 284 -1 285 286 287 -1 288 289 290 -1 291 292 293 -1 294 295 296 -1 297 298 299 -1 300 301 302 -1 303 304 305 -1 306 307 308 -1 309 310 311 -1 312 313 314 -1 315 316 317 -1 318 319 320 -1 321 322 323 -1 324 325 326 -1 327 328 329 -1 330 331 332 -1 333 334 335 -1 336 337 338 -1 339 340 341 -1 342 343 344 -1 345 346 347 -1 348 349 350 -1 351 352 353 -1 354 355 356 -1 357 358 359 -1 360 361 362 -1 363 364 365 -1 366 367 368 -1 369 370 371 -1 372 373 374 -1 375 376 377 -1 378 379 380 -1 381 382 383 -1 384 385 386 -1 387 388 389 -1 390 391 392 -1 393 394 395 -1 396 397 398 -1 399 400 401 -1 402 403 404 -1 405 406 407 -1 408 409 410 -1 411 412 413 -1 414 415 416 -1 417 418 419 -1 420 421 422 -1 423 424 425 -1 426 427 428 -1 429 430 431 -1 432 433 434 -1 435 436 437 -1 438 439 440 -1 441 442 443 -1 444 445 446 -1 447 448 449 -1 450 451 452 -1 453 454 455 -1 456 457 458 -1 459 460 461 -1 462 463 464 -1 465 466 467 -1 468 469 470 -1 471 472 473 -1 474 475 476 -1 477 478 479 -1 480 481 482 -1 483 484 485 -1 486 487 488 -1 489 490 491 -1 492 493 494 -1 495 496 497 -1 498 499 500 -1 501 502 503 -1 504 505 506 -1 507 508 509 -1 510 511 512 -1 513 514 515 -1 516 517 518 -1 519 520 521 -1 522 523 524 -1 525 526 527 -1 528 529 530 -1 531 532 533 -1 534 535 536 -1 537 538 539 -1 540 541 542 -1 543 544 545 -1 546 547 548 -1 549 550 551 -1 552 553 554 -1 555 556 557 -1 558 559 560 -1 561 562 563 -1
389 | ]
390 | creaseAngle 1
391 | }
392 | }
393 | ]
394 | }
395 | DEF WHITE_BUTTON Transform {
396 | translation -0.136623 0.0706176 0.0923371
397 | rotation 1 0 0 0
398 | children [
399 | Shape {
400 | appearance PBRAppearance {
401 | metalness 0
402 | roughness 0.3
403 | }
404 | geometry IndexedFaceSet {
405 | coord DEF coord_whiteButton Coordinate {
406 | point [
407 | -0.0045 -0.003182 -0.003182, -0.0045 -0.0045 0 -0.0045 -0.003182 0.003182, -0.0045 0 0.0045 -0.0045 0.003182 0.003182, -0.0045 0.0045 -0 -0.0045 0.003182 -0.003182, -0.0045 0 -0.0045 0.0045 -0.003182 -0.003182, 0.0045 -0.0045 -0 0.0045 -0.003182 0.003182, 0.0045 0 0.0045 0.0045 0.003182 0.003182, 0.0045 0.0045 -0 0.0045 0.003182 -0.003182, 0.0045 -0 -0.0045 -0.0045 -0 0
408 | ]
409 | }
410 | coordIndex [
411 | 16 0 1 -1 16 1 2 -1 16 2 3 -1 16 3 4 -1 16 4 5 -1 16 5 6 -1 16 6 7 -1 7 0 16 -1 8 0 7 -1 8 7 15 -1 6 14 15 -1 6 15 7 -1 5 13 14 -1 5 14 6 -1 4 12 13 -1 4 13 5 -1 3 11 12 -1 3 12 4 -1 2 10 11 -1 2 11 3 -1 1 9 10 -1 1 10 2 -1 0 8 9 -1 0 9 1 -1
412 | ]
413 | creaseAngle 1.5
414 | }
415 | }
416 | ]
417 | }
418 | ]
419 | }
420 | DEF CASTER_WHEEL HingeJoint {
421 | jointParameters HingeJointParameters {
422 | axis 0 1 0
423 | anchor 0 -0.0011939 0.191844
424 | staticFriction 0.05
425 | }
426 | endPoint Solid {
427 | translation 0 -0.0011939 0.191844
428 | rotation 0 1 0 0
429 | children [
430 | DEF casterWheelRim HingeJoint {
431 | jointParameters HingeJointParameters {
432 | axis 1 0 0
433 | anchor 0 -0.0521014 0.012843
434 | }
435 | endPoint Solid {
436 | translation 0 -0.0521014 0.012843
437 | rotation 1 0 0 0
438 | children [
439 | DEF CASTER_WHEEL_RIM_SHAPE Shape {
440 | appearance PBRAppearance {
441 | metalness 0
442 | roughness 0.2
443 | baseColor 0 0 0
444 | }
445 | geometry IndexedFaceSet {
446 | coord DEF coord_CASTER_WHEEL_RIM Coordinate {
447 | point [
448 | -0.0197163 -0 -0.0115213, 0.0198537 0.0057608 -0.0099777 0.0151734 0.0078882 -0.0136625, -0.015036 0.007888 -0.0136626 -0.0197163 0.0057605 -0.0099778, -0.0197164 0.0099775 -0.0057608 -0.0150361 0.0136623 -0.0078882, 0.0151733 0.0136628 -0.0078879 0.0198537 0.0099781 -0.0057605, 0.0198536 0.0115217 0 0.0151731 0.0157764 0, -0.0150362 0.0157759 -0 -0.0197165 0.011521 -0, -0.0197166 0.0099775 0.0057601 -0.0150364 0.0136623 0.0078877, 0.015173 0.0136628 0.0078885 0.0198535 0.0099781 0.0057612, 0.0198534 0.0057608 0.0099784 0.0151729 0.0078882 0.0136631, -0.0150365 0.0078879 0.0136621 -0.0197167 0.0057605 0.0099771, -0.0197167 0 0.0115206 -0.0150365 -0 0.0157756, 0.0151729 -0 0.0157767 0.0198533 0 0.011522, 0.0198534 -0.0057608 0.0099784 0.0151729 -0.0078882 0.013663, -0.0150365 -0.0078879 0.0136621 -0.0197167 -0.0057605 0.0099771, -0.0198524 -0 -0 -0.0197166 -0.0099775 0.0057601, -0.0150364 -0.0136623 0.0078877 0.015173 -0.0136628 0.0078885, 0.0198535 -0.0099781 0.0057612 0.0198538 -0 0, 0.0198536 -0.0115217 0 0.0151731 -0.0157764 0, -0.0150362 -0.0157759 -0 -0.0197165 -0.011521 -0, -0.0197164 -0.0099775 -0.0057608 -0.0150361 -0.0136623 -0.0078882, 0.0151733 -0.0136628 -0.0078879 0.0198537 -0.0099781 -0.0057605, 0.0198537 -0.0057608 -0.0099777 0.0151734 -0.0078882 -0.0136625, -0.015036 -0.0078879 -0.0136626 -0.0197163 -0.0057605 -0.0099778, -0.015036 0 -0.0157762 0.0151734 0 -0.0157762, 0.0198538 -0 -0.0115213
449 | ]
450 | }
451 | coordIndex [
452 | 0 29 4 -1 34 49 1 -1 34 1 8 -1 4 29 5 -1 5 29 12 -1 34 8 9 -1 34 9 16 -1 12 29 13 -1 13 29 20 -1 34 16 17 -1 34 17 24 -1 20 29 21 -1 21 29 28 -1 34 24 25 -1 34 25 33 -1 28 29 30 -1 30 29 38 -1 34 33 35 -1 34 35 42 -1 38 29 39 -1 39 29 46 -1 34 42 43 -1 34 43 49 -1 29 0 46 -1 46 0 45 -1 45 0 47 -1 44 45 47 -1 44 47 48 -1 43 44 48 -1 43 48 49 -1 42 41 44 -1 42 44 43 -1 41 40 45 -1 41 45 44 -1 40 39 46 -1 40 46 45 -1 37 38 39 -1 37 39 40 -1 36 37 40 -1 36 40 41 -1 35 36 41 -1 35 41 42 -1 33 32 36 -1 33 36 35 -1 32 31 37 -1 32 37 36 -1 31 30 38 -1 31 38 37 -1 27 28 30 -1 27 30 31 -1 26 27 31 -1 26 31 32 -1 25 26 32 -1 25 32 33 -1 24 23 26 -1 24 26 25 -1 23 22 27 -1 23 27 26 -1 22 21 28 -1 22 28 27 -1 19 20 21 -1 19 21 22 -1 18 19 22 -1 18 22 23 -1 17 18 23 -1 17 23 24 -1 16 15 18 -1 16 18 17 -1 15 14 19 -1 15 19 18 -1 14 13 20 -1 14 20 19 -1 11 12 13 -1 11 13 14 -1 10 11 14 -1 10 14 15 -1 9 10 15 -1 9 15 16 -1 8 7 10 -1 8 10 9 -1 7 6 11 -1 7 11 10 -1 6 5 12 -1 6 12 11 -1 3 4 5 -1 3 5 6 -1 2 3 6 -1 2 6 7 -1 1 2 7 -1 1 7 8 -1 49 48 2 -1 49 2 1 -1 48 47 3 -1 48 3 2 -1 47 0 4 -1 47 4 3 -1
453 | ]
454 | creaseAngle 1
455 | }
456 | }
457 | DEF CASTER_WHEEL_TIRE_SHAPE Shape {
458 | appearance PBRAppearance {
459 | roughness 0.7
460 | metalness 0
461 | baseColorMap ImageTexture {
462 | url [
463 | "textures/caster_wheel_base_color.jpg"
464 | ]
465 | }
466 | roughnessMap ImageTexture {
467 | url [
468 | "textures/caster_wheel_roughness.jpg"
469 | ]
470 | }
471 | normalMap ImageTexture {
472 | url [
473 | "textures/caster_wheel_normal.jpg"
474 | ]
475 | }
476 | occlusionMap ImageTexture {
477 | url [
478 | "textures/caster_wheel_occlusion.jpg"
479 | ]
480 | }
481 | }
482 | geometry IndexedFaceSet {
483 | coord Coordinate {
484 | point [
485 | -0.0156852 0.0301219 0, 0.0155292 0.0301219 0 0.0155292 0.0260863 0.015061, 0.0120956 0.0302764 0.0174801 0.0074134 0.0331148 0.0191188, -0.0075695 0.0331148 0.0191188 -0.0122517 0.0302764 0.0174801, -0.0156852 0.0260863 0.015061 -0.0156852 0.015061 0.0260863, -0.0122517 0.0174801 0.0302764 -0.0075695 0.0191188 0.0331148, 0.0074134 0.0191188 0.0331148 0.0120956 0.0174801 0.0302764, 0.0155292 0.015061 0.0260863 0.0155292 0 0.0301219, 0.0120956 -0 0.0349601 0.0074134 -0 0.0382377, -0.0075695 -0 0.0382377 -0.0122517 -0 0.0349601, -0.0156852 0 0.0301219 -0.0155292 -0 0, -0.0156852 -0.015061 0.0260863 -0.0122517 -0.0174801 0.0302764, -0.0075695 -0.0191188 0.0331148 0.0074134 -0.0191188 0.0331148, 0.0120956 -0.0174801 0.0302764 0.0155292 -0.015061 0.0260863, 0.0155292 -0 0 0.0155292 -0.0260863 0.015061, 0.0120956 -0.0302764 0.0174801 0.0074134 -0.0331148 0.0191188, -0.0075695 -0.0331148 0.0191188 -0.0122517 -0.0302764 0.0174801, -0.0156852 -0.0260863 0.015061 -0.0156852 -0.0301219 0, -0.0122517 -0.0349601 0 -0.0075695 -0.0382376 0, 0.0074134 -0.0382376 0 0.0120956 -0.0349601 0, 0.0155292 -0.0301219 0 0.0155292 -0.0260863 -0.0150609, 0.0120956 -0.0302764 -0.0174801 0.0074134 -0.0331148 -0.0191188, -0.0075695 -0.0331148 -0.0191188 -0.0122517 -0.0302764 -0.0174801, -0.0156852 -0.0260863 -0.0150609 -0.0156852 -0.015061 -0.0260863, -0.0122517 -0.0174801 -0.0302763 -0.0075695 -0.0191188 -0.0331148, 0.0074134 -0.0191188 -0.0331148 0.0120956 -0.0174801 -0.0302763, 0.0155292 -0.015061 -0.0260863 0.0155292 0 -0.0301219, 0.0120956 0 -0.0349601 0.0074134 0 -0.0382376, -0.0075695 0 -0.0382376 -0.0122517 0 -0.0349601, -0.0156852 0 -0.0301219 -0.0156852 0.015061 -0.0260863, -0.0122517 0.0174801 -0.0302763 -0.0075695 0.0191188 -0.0331147, 0.0074134 0.0191188 -0.0331147 0.0120956 0.0174801 -0.0302763, 0.0155292 0.015061 -0.0260863 0.0155292 0.0260863 -0.0150609, 0.0120956 0.0302764 -0.01748 0.0074134 0.0331148 -0.0191188, -0.0075695 0.0331148 -0.0191188 -0.0122517 0.0302764 -0.01748, -0.0156852 0.0260863 -0.0150609 -0.0122517 0.0349601 0, -0.0075695 0.0382376 0 0.0074134 0.0382376 0, 0.0120956 0.0349601 0
486 | ]
487 | }
488 | texCoord TextureCoordinate {
489 | point [
490 | 0.507218 0.626647, 0.507227 0.626774, 0.507208 0.626773 0.507207 0.626774, 0.507211 0.6269, 0.50719 0.626798 0.50719 0.626798, 0.507208 0.626911, 0.507179 0.62685 0.507213 0.626643, 0.507208 0.626773, 0.507191 0.626746 0.507208 0.626638, 0.507191 0.626746, 0.507179 0.6267 0.507179 0.62685, 0.507206 0.626926, 0.507173 0.626909 0.507173 0.626909, 0.507206 0.626943, 0.507172 0.626974 0.507205 0.626626, 0.507179 0.6267, 0.507172 0.626641 0.507204 0.62661, 0.507172 0.626641, 0.507172 0.62658 0.507172 0.626974, 0.507206 0.626959, 0.507179 0.627035 0.507179 0.627035, 0.507209 0.626973, 0.507191 0.627082 0.507204 0.626595, 0.507172 0.62658, 0.507179 0.626523 0.507207 0.626582, 0.507179 0.626523, 0.50719 0.62648 0.507191 0.627082, 0.507213 0.626982, 0.507208 0.627108 0.507208 0.627108, 0.507217 0.626987, 0.507225 0.6271 0.50721 0.626574, 0.50719 0.62648, 0.507206 0.626456 0.507214 0.626571, 0.507206 0.626456, 0.507223 0.626448 0.507225 0.6271, 0.507221 0.626984, 0.507241 0.627077 0.507241 0.627077, 0.507225 0.626976, 0.507252 0.627034 0.507218 0.626568, 0.507223 0.626448, 0.507238 0.626472 0.507222 0.626576, 0.507238 0.626472, 0.50725 0.626516 0.507252 0.627034, 0.507227 0.626963, 0.507258 0.626978 0.507228 0.626948, 0.507258 0.626918, 0.507258 0.626978 0.507224 0.626589, 0.50725 0.626516, 0.507257 0.626574 0.67452 -1.97972, 0.319963 -1.97972, 0.320526 -2.55258 0.67452 -1.97972, 0.320526 -2.55258, 0.67452 -2.55258 0.992938 -1.97972, 0.830837 -1.97972, 0.830837 -2.55258 0.992938 -1.97972, 0.830837 -2.55258, 0.992938 -2.55258 0.830837 -1.97972, 0.67452 -1.97972, 0.67452 -2.55258 0.830837 -1.97972, 0.67452 -2.55258, 0.830837 -2.55258 0.319963 -1.97972, 0.175009 -1.97972, 0.175009 -2.55258 0.319963 -1.97972, 0.175009 -2.55258, 0.320526 -2.55258 0.0116031 -1.97972, 0.0116031 -2.55258, 0.175009 -1.97972 0.175009 -1.97972, 0.0116031 -2.55258, 0.175009 -2.55258 0.175009 -1.46882, 0.0116031 -1.46882, 0.0116031 -1.97972 0.175009 -1.46882, 0.0116031 -1.97972, 0.175009 -1.97972 0.319963 -1.46882, 0.175009 -1.46882, 0.175009 -1.97972 0.319963 -1.46882, 0.175009 -1.97972, 0.319963 -1.97972 0.830837 -1.46882, 0.67452 -1.46882, 0.67452 -1.97972 0.830837 -1.46882, 0.67452 -1.97972, 0.830837 -1.97972 0.992938 -1.46882, 0.830837 -1.46882, 0.830837 -1.97972 0.992938 -1.46882, 0.830837 -1.97972, 0.992938 -1.97972 0.67452 -1.46882, 0.319963 -1.46882, 0.319963 -1.97972 0.67452 -1.46882, 0.319963 -1.97972, 0.67452 -1.97972 0.67452 -0.987906, 0.319963 -0.987906, 0.319963 -1.46882 0.67452 -0.987906, 0.319963 -1.46882, 0.67452 -1.46882 0.992938 -0.987906, 0.830837 -0.987906, 0.830837 -1.46882 0.992938 -0.987906, 0.830837 -1.46882, 0.992938 -1.46882 0.830837 -0.987906, 0.67452 -0.987906, 0.67452 -1.46882 0.830837 -0.987906, 0.67452 -1.46882, 0.830837 -1.46882 0.319963 -0.987906, 0.175009 -0.987906, 0.175009 -1.46882 0.319963 -0.987906, 0.175009 -1.46882, 0.319963 -1.46882 0.175009 -0.987906, 0.0116031 -0.987906, 0.0116031 -1.46882 0.175009 -0.987906, 0.0116031 -1.46882, 0.175009 -1.46882 0.175009 -0.523249, 0.0116031 -0.523249, 0.0116031 -0.987906 0.175009 -0.523249, 0.0116031 -0.987906, 0.175009 -0.987906 0.319963 -0.523249, 0.175009 -0.523249, 0.175009 -0.987906 0.319963 -0.523249, 0.175009 -0.987906, 0.319963 -0.987906 0.830837 -0.523249, 0.67452 -0.523249, 0.67452 -0.987906 0.830837 -0.523249, 0.67452 -0.987906, 0.830837 -0.987906 0.992938 -0.523249, 0.830837 -0.523249, 0.830837 -0.987906 0.992938 -0.523249, 0.830837 -0.987906, 0.992938 -0.987906 0.67452 -0.523249, 0.319963 -0.523249, 0.319963 -0.987906 0.67452 -0.523249, 0.319963 -0.987906, 0.67452 -0.987906 0.67452 -0.0712502, 0.319963 -0.0712502, 0.319963 -0.523249 0.67452 -0.0712502, 0.319963 -0.523249, 0.67452 -0.523249 0.992938 -0.0712502, 0.830837 -0.0712502, 0.830837 -0.523249 0.992938 -0.0712502, 0.830837 -0.523249, 0.992938 -0.523249 0.830837 -0.0712502, 0.67452 -0.0712502, 0.67452 -0.523249 0.830837 -0.0712502, 0.67452 -0.523249, 0.830837 -0.523249 0.319963 -0.0712502, 0.175009 -0.0712502, 0.175009 -0.523249 0.319963 -0.0712502, 0.175009 -0.523249, 0.319963 -0.523249 0.175009 -0.0712502, 0.0116031 -0.0712502, 0.0116031 -0.523249 0.175009 -0.0712502, 0.0116031 -0.523249, 0.175009 -0.523249 0.175009 0.369622, 0.0116031 0.369622, 0.0116031 -0.0712502 0.175009 0.369622, 0.0116031 -0.0712502, 0.175009 -0.0712502 0.319963 0.369622, 0.175009 0.369622, 0.175009 -0.0712502 0.319963 0.369622, 0.175009 -0.0712502, 0.319963 -0.0712502 0.830837 0.369622, 0.67452 0.369622, 0.67452 -0.0712502 0.830837 0.369622, 0.67452 -0.0712502, 0.830837 -0.0712502 0.992938 0.369622, 0.830837 0.369622, 0.830837 -0.0712502 0.992938 0.369622, 0.830837 -0.0712502, 0.992938 -0.0712502 0.67452 0.369622, 0.319963 0.369622, 0.319963 -0.0712502 0.67452 0.369622, 0.319963 -0.0712502, 0.67452 -0.0712502 0.67452 0.803526, 0.319963 0.803526, 0.319963 0.369622 0.67452 0.803526, 0.319963 0.369622, 0.67452 0.369622 0.992938 0.803526, 0.830837 0.803526, 0.830837 0.369622 0.992938 0.803526, 0.830837 0.369622, 0.992938 0.369622 0.830837 0.803526, 0.67452 0.803526, 0.67452 0.369622 0.830837 0.803526, 0.67452 0.369622, 0.830837 0.369622 0.319963 0.803526, 0.175009 0.803526, 0.175009 0.369622 0.319963 0.803526, 0.175009 0.369622, 0.319963 0.369622 0.175009 0.803526, 0.0116031 0.803526, 0.0116031 0.369622 0.175009 0.803526, 0.0116031 0.369622, 0.175009 0.369622 0.175009 1.23059, 0.0116031 1.23059, 0.0116031 0.803526 0.175009 1.23059, 0.0116031 0.803526, 0.175009 0.803526 0.319963 1.23059, 0.175009 1.23059, 0.175009 0.803526 0.319963 1.23059, 0.175009 0.803526, 0.319963 0.803526 0.830837 1.23059, 0.67452 1.23059, 0.67452 0.803526 0.830837 1.23059, 0.67452 0.803526, 0.830837 0.803526 0.992938 1.23059, 0.830837 1.23059, 0.830837 0.803526 0.992938 1.23059, 0.830837 0.803526, 0.992938 0.803526 0.67452 1.23059, 0.319963 1.23059, 0.319963 0.803526 0.67452 1.23059, 0.319963 0.803526, 0.67452 0.803526 0.67452 1.64826, 0.319963 1.64826, 0.319963 1.23059 0.67452 1.64826, 0.319963 1.23059, 0.67452 1.23059 0.992938 1.64826, 0.830837 1.64826, 0.830837 1.23059 0.992938 1.64826, 0.830837 1.23059, 0.992938 1.23059 0.830837 1.64826, 0.67452 1.64826, 0.67452 1.23059 0.830837 1.64826, 0.67452 1.23059, 0.830837 1.23059 0.319963 1.64826, 0.175009 1.64826, 0.175009 1.23059 0.319963 1.64826, 0.175009 1.23059, 0.319963 1.23059 0.175009 1.64826, 0.0116031 1.64826, 0.0116031 1.23059 0.175009 1.64826, 0.0116031 1.23059, 0.175009 1.23059 0.175009 2.05885, 0.0116031 2.05885, 0.0116031 1.64826 0.175009 2.05885, 0.0116031 1.64826, 0.175009 1.64826 0.319963 2.05885, 0.175009 2.05885, 0.175009 1.64826 0.319963 2.05885, 0.175009 1.64826, 0.319963 1.64826 0.830837 2.05885, 0.67452 2.05885, 0.67452 1.64826 0.830837 2.05885, 0.67452 1.64826, 0.830837 1.64826 0.992938 2.05885, 0.830837 2.05885, 0.830837 1.64826 0.992938 2.05885, 0.830837 1.64826, 0.992938 1.64826 0.67452 2.05885, 0.319963 2.05885, 0.319963 1.64826 0.67452 2.05885, 0.319963 1.64826, 0.67452 1.64826 0.67452 2.47924, 0.319963 2.47924, 0.319963 2.05885 0.67452 2.47924, 0.319963 2.05885, 0.67452 2.05885 0.992938 2.47924, 0.830837 2.47924, 0.830837 2.05885 0.992938 2.47924, 0.830837 2.05885, 0.992938 2.05885 0.830837 2.47924, 0.67452 2.47924, 0.67452 2.05885 0.830837 2.47924, 0.67452 2.05885, 0.830837 2.05885 0.319963 2.47924, 0.175009 2.47924, 0.175009 2.05885 0.319963 2.47924, 0.175009 2.05885, 0.319963 2.05885 0.175009 2.47924, 0.0116031 2.47924, 0.0116031 2.05885 0.175009 2.47924, 0.0116031 2.05885, 0.175009 2.05885 0.175009 2.94553, 0.0116031 2.94553, 0.0116031 2.47924 0.175009 2.94553, 0.0116031 2.47924, 0.175009 2.47924 0.319963 2.94553, 0.175009 2.94553, 0.175009 2.47924 0.319963 2.94553, 0.175009 2.47924, 0.319963 2.47924 0.830837 2.94553, 0.67452 2.94553, 0.67452 2.47924 0.830837 2.94553, 0.67452 2.47924, 0.830837 2.47924 0.992938 2.94553, 0.830837 2.94553, 0.830837 2.47924 0.992938 2.94553, 0.830837 2.47924, 0.992938 2.47924 0.67452 2.94553, 0.319963 2.94553, 0.319963 2.47924 0.67452 2.94553, 0.319963 2.47924, 0.67452 2.47924
491 | ]
492 | }
493 | coordIndex [
494 | 27 1 2 -1 0 20 7 -1 7 20 8 -1 27 2 13 -1 27 13 14 -1 8 20 19 -1 19 20 21 -1 27 14 26 -1 27 26 28 -1 21 20 33 -1 33 20 34 -1 27 28 39 -1 27 39 40 -1 34 20 45 -1 45 20 46 -1 27 40 51 -1 27 51 52 -1 46 20 57 -1 57 20 58 -1 27 52 63 -1 27 63 64 -1 58 20 69 -1 20 0 69 -1 27 64 1 -1 66 67 71 -1 66 71 72 -1 64 65 73 -1 64 73 1 -1 65 66 72 -1 65 72 73 -1 67 68 70 -1 67 70 71 -1 69 0 68 -1 68 0 70 -1 59 58 69 -1 59 69 68 -1 60 59 68 -1 60 68 67 -1 62 61 66 -1 62 66 65 -1 63 62 65 -1 63 65 64 -1 61 60 67 -1 61 67 66 -1 54 55 60 -1 54 60 61 -1 52 53 62 -1 52 62 63 -1 53 54 61 -1 53 61 62 -1 55 56 59 -1 55 59 60 -1 56 57 58 -1 56 58 59 -1 47 46 57 -1 47 57 56 -1 48 47 56 -1 48 56 55 -1 50 49 54 -1 50 54 53 -1 51 50 53 -1 51 53 52 -1 49 48 55 -1 49 55 54 -1 42 43 48 -1 42 48 49 -1 40 41 50 -1 40 50 51 -1 41 42 49 -1 41 49 50 -1 43 44 47 -1 43 47 48 -1 44 45 46 -1 44 46 47 -1 35 34 45 -1 35 45 44 -1 36 35 44 -1 36 44 43 -1 38 37 42 -1 38 42 41 -1 39 38 41 -1 39 41 40 -1 37 36 43 -1 37 43 42 -1 30 31 36 -1 30 36 37 -1 28 29 38 -1 28 38 39 -1 29 30 37 -1 29 37 38 -1 31 32 35 -1 31 35 36 -1 32 33 34 -1 32 34 35 -1 22 21 33 -1 22 33 32 -1 23 22 32 -1 23 32 31 -1 25 24 30 -1 25 30 29 -1 26 25 29 -1 26 29 28 -1 24 23 31 -1 24 31 30 -1 16 17 23 -1 16 23 24 -1 14 15 25 -1 14 25 26 -1 15 16 24 -1 15 24 25 -1 17 18 22 -1 17 22 23 -1 18 19 21 -1 18 21 22 -1 9 8 19 -1 9 19 18 -1 10 9 18 -1 10 18 17 -1 12 11 16 -1 12 16 15 -1 13 12 15 -1 13 15 14 -1 11 10 17 -1 11 17 16 -1 4 5 10 -1 4 10 11 -1 2 3 12 -1 2 12 13 -1 3 4 11 -1 3 11 12 -1 5 6 9 -1 5 9 10 -1 6 7 8 -1 6 8 9 -1 70 0 7 -1 70 7 6 -1 71 70 6 -1 71 6 5 -1 73 72 4 -1 73 4 3 -1 1 73 3 -1 1 3 2 -1 72 71 5 -1 72 5 4 -1
495 | ]
496 | texCoordIndex [
497 | 0 1 2 -1 3 4 5 -1 6 7 8 -1 9 10 11 -1 12 13 14 -1 15 16 17 -1 18 19 20 -1 21 22 23 -1 24 25 26 -1 27 28 29 -1 30 31 32 -1 33 34 35 -1 36 37 38 -1 39 40 41 -1 42 43 44 -1 45 46 47 -1 48 49 50 -1 51 52 53 -1 54 55 56 -1 57 58 59 -1 60 61 62 -1 63 64 65 -1 66 67 68 -1 69 70 71 -1 72 73 74 -1 75 76 77 -1 78 79 80 -1 81 82 83 -1 84 85 86 -1 87 88 89 -1 90 91 92 -1 93 94 95 -1 96 97 98 -1 99 100 101 -1 102 103 104 -1 105 106 107 -1 108 109 110 -1 111 112 113 -1 114 115 116 -1 117 118 119 -1 120 121 122 -1 123 124 125 -1 126 127 128 -1 129 130 131 -1 132 133 134 -1 135 136 137 -1 138 139 140 -1 141 142 143 -1 144 145 146 -1 147 148 149 -1 150 151 152 -1 153 154 155 -1 156 157 158 -1 159 160 161 -1 162 163 164 -1 165 166 167 -1 168 169 170 -1 171 172 173 -1 174 175 176 -1 177 178 179 -1 180 181 182 -1 183 184 185 -1 186 187 188 -1 189 190 191 -1 192 193 194 -1 195 196 197 -1 198 199 200 -1 201 202 203 -1 204 205 206 -1 207 208 209 -1 210 211 212 -1 213 214 215 -1 216 217 218 -1 219 220 221 -1 222 223 224 -1 225 226 227 -1 228 229 230 -1 231 232 233 -1 234 235 236 -1 237 238 239 -1 240 241 242 -1 243 244 245 -1 246 247 248 -1 249 250 251 -1 252 253 254 -1 255 256 257 -1 258 259 260 -1 261 262 263 -1 264 265 266 -1 267 268 269 -1 270 271 272 -1 273 274 275 -1 276 277 278 -1 279 280 281 -1 282 283 284 -1 285 286 287 -1 288 289 290 -1 291 292 293 -1 294 295 296 -1 297 298 299 -1 300 301 302 -1 303 304 305 -1 306 307 308 -1 309 310 311 -1 312 313 314 -1 315 316 317 -1 318 319 320 -1 321 322 323 -1 324 325 326 -1 327 328 329 -1 330 331 332 -1 333 334 335 -1 336 337 338 -1 339 340 341 -1 342 343 344 -1 345 346 347 -1 348 349 350 -1 351 352 353 -1 354 355 356 -1 357 358 359 -1 360 361 362 -1 363 364 365 -1 366 367 368 -1 369 370 371 -1 372 373 374 -1 375 376 377 -1 378 379 380 -1 381 382 383 -1 384 385 386 -1 387 388 389 -1 390 391 392 -1 393 394 395 -1 396 397 398 -1 399 400 401 -1 402 403 404 -1 405 406 407 -1 408 409 410 -1 411 412 413 -1 414 415 416 -1 417 418 419 -1 420 421 422 -1 423 424 425 -1 426 427 428 -1 429 430 431 -1
498 | ]
499 | creaseAngle 1
500 | }
501 | }
502 | ]
503 | boundingObject Transform {
504 | rotation 0 0 1 1.5708
505 | children [
506 | Cylinder {
507 | height 0.025
508 | radius 0.0375
509 | subdivision 24
510 | }
511 | ]
512 | }
513 | physics Physics {
514 | }
515 | }
516 | }
517 | DEF FORK_SHAPE Shape {
518 | appearance PBRAppearance {
519 | metalness 0
520 | baseColor 0 0 0
521 | roughness 0.2
522 | }
523 | geometry IndexedFaceSet {
524 | coord DEF coord_FORK Coordinate {
525 | point [
526 | 0.0250514 -0.0530331 0.0236063, 0.0250514 -0.0607131 0.0215853 0.0250514 -0.0631384 0.0135011, 0.0250514 -0.0590963 0.0054169 0.0250514 -0.0352479 -0.0147409, 0.0250514 0.0023437 -0.0147936 0.0250514 0.002291 0.0082464, 0.0250514 -0.0312058 0.0179474 0.0195734 -0.0312058 0.0179474, 0.0195734 0.002291 0.0082464 0.0195734 0.0023437 -0.0147936, 0.0195734 -0.0352479 -0.0147409 0.0195734 -0.0590963 0.0054169, 0.0195734 -0.0631384 0.0135011 0.0195734 -0.0607131 0.0215853, 0.0195734 -0.0530331 0.0236063 -0.0250514 -0.0530331 0.0236063, -0.0250514 -0.0607131 0.0215853 -0.0250514 -0.0631384 0.0135011, -0.0250514 -0.0590963 0.0054169 -0.0250514 -0.0352479 -0.0147409, -0.0250514 0.0023437 -0.0147936 -0.0250514 0.002291 0.0082464, -0.0250514 -0.0312058 0.0179474 -0.0195735 -0.0312058 0.0179474, -0.0195735 0.002291 0.0082464 -0.0195735 0.0023437 -0.0147936, -0.0195735 -0.0352479 -0.0147409 -0.0195735 -0.0590963 0.0054169, -0.0195735 -0.0631384 0.0135011 -0.0195735 -0.0607131 0.0215853, -0.0195735 -0.0530331 0.0236063
527 | ]
528 | }
529 | coordIndex [
530 | 27 26 25 -1 27 25 24 -1 24 31 28 -1 24 28 27 -1 31 30 29 -1 31 29 28 -1 31 24 23 -1 31 23 16 -1 26 27 20 -1 26 20 21 -1 24 25 22 -1 24 22 23 -1 25 26 21 -1 25 21 22 -1 27 28 19 -1 27 19 20 -1 28 29 18 -1 28 18 19 -1 29 30 17 -1 29 17 18 -1 30 31 16 -1 30 16 17 -1 22 21 20 -1 22 20 23 -1 23 20 19 -1 23 19 16 -1 18 17 16 -1 18 16 19 -1 13 14 15 -1 13 15 12 -1 8 11 12 -1 8 12 15 -1 9 10 11 -1 9 11 8 -1 1 0 15 -1 1 15 14 -1 2 1 14 -1 2 14 13 -1 3 2 13 -1 3 13 12 -1 4 3 12 -1 4 12 11 -1 6 5 10 -1 6 10 9 -1 7 6 9 -1 7 9 8 -1 5 4 11 -1 5 11 10 -1 0 7 8 -1 0 8 15 -1 0 1 2 -1 0 2 3 -1 7 0 3 -1 7 3 4 -1 4 5 6 -1 4 6 7 -1
531 | ]
532 | creaseAngle 1
533 | }
534 | }
535 | DEF ROTATING_JOINT_SHAPE Shape {
536 | appearance PBRAppearance {
537 | baseColor 0.4 0.4 0.4
538 | roughness 0.3
539 | }
540 | geometry IndexedFaceSet {
541 | coord DEF coord_rotatingJointMesh Coordinate {
542 | point [
543 | -0.0333061 0.0029861 -0.0199542, 0.0333061 0.0029861 -0.0199542 0.0268745 -0.0029861 -0.0199542, -0.0273339 -0.0029861 -0.0199542 -0.0273339 -0.0029861 0.0199542, 0.0268745 -0.0029861 0.0199542 0.0333061 0.0029861 0.0199542, -0.0333061 0.0029861 0.0199542
544 | ]
545 | }
546 | coordIndex [
547 | 4 5 7 -1 5 6 7 -1 0 7 6 -1 0 6 1 -1 1 6 5 -1 1 5 2 -1 2 5 4 -1 2 4 3 -1 7 0 3 -1 7 3 4 -1 3 0 2 -1 0 1 2 -1
548 | ]
549 | creaseAngle 1
550 | }
551 | }
552 | ]
553 | name "caster wheel"
554 | boundingObject Transform {
555 | translation 0 -0.032 0.0031
556 | rotation 1 0 0 1.25
557 | children [
558 | Box {
559 | size 0.05 0.028 0.067
560 | }
561 | ]
562 | }
563 | physics Physics {
564 | }
565 | }
566 | }
567 | DEF GREEN_LED LED {
568 | translation -0.130323 0.0802227 0.0823476
569 | rotation 1 0 0 0
570 | children [
571 | Shape {
572 | appearance PBRAppearance {
573 | baseColor 0 1 0
574 | metalness 0
575 | roughness 0.3
576 | transparency 0.440172
577 | }
578 | geometry DEF LED_SHAPE Sphere {
579 | radius 0.004
580 | subdivision 2
581 | }
582 | }
583 | ]
584 | name "green led"
585 | color [
586 | 0.564706 0.933333 0.564706
587 | ]
588 | }
589 | DEF LEFT_WHEEL HingeJoint {
590 | device [
591 | RotationalMotor {
592 | name "left wheel"
593 | maxVelocity 12.3
594 | }
595 | PositionSensor {
596 | name "left wheel sensor"
597 | }
598 | ]
599 | jointParameters HingeJointParameters {
600 | axis -1 0 0
601 | anchor -0.165 -0.0001156 0
602 | }
603 | endPoint Solid {
604 | translation -0.165 -0.0001156 0
605 | rotation -1 0 0 0
606 | children [
607 | DEF BLACK_CYLINDER_SHAPE Shape {
608 | appearance PBRAppearance {
609 | baseColor 0 0.0051864 0
610 | roughness 0.3
611 | metalness 0
612 | }
613 | geometry IndexedFaceSet {
614 | coord Coordinate {
615 | point [
616 | -0.0241117 0.0067816 -0.0017403, -0.0241117 0.0067431 0.0018836 -0.0241117 0.0048978 0.0050029, -0.0241117 0.0017403 0.0067816 -0.0241117 -0.0018837 0.0067431, -0.0241117 -0.0050029 0.0048979 -0.0241117 -0.0067816 0.0017402, -0.0241117 -0.0067431 -0.0018837 -0.0241117 -0.0048978 -0.0050029, -0.0241117 -0.0017403 -0.0067816 -0.0241117 0.0018837 -0.0067431, -0.0241117 0.0050029 -0.0048979 -0.0219651 0.0067816 -0.0017403, -0.0219651 0.0067434 0.0018838 -0.0219651 0.004898 0.0050029, -0.0219651 0.0017402 0.0067815 -0.0219651 -0.0018837 0.0067431, -0.0219651 -0.0050029 0.0048979 -0.0219651 -0.0067815 0.0017403, -0.0219651 -0.0067431 -0.0018837 -0.0219651 -0.0048978 -0.0050029, -0.0219651 -0.0017403 -0.0067816 -0.0219651 0.0018837 -0.0067431, -0.0219651 0.0050029 -0.0048979 -0.0241117 0 0
617 | ]
618 | }
619 | coordIndex [
620 | 1 0 24 -1 24 2 1 -1 24 3 2 -1 24 4 3 -1 24 5 4 -1 24 6 5 -1 24 7 6 -1 24 8 7 -1 24 9 8 -1 24 10 9 -1 24 11 10 -1 24 0 11 -1 11 0 12 -1 12 23 11 -1 10 23 22 -1 10 11 23 -1 9 22 21 -1 9 10 22 -1 8 21 20 -1 8 9 21 -1 7 20 19 -1 7 8 20 -1 6 19 18 -1 6 7 19 -1 5 18 17 -1 5 6 18 -1 4 17 16 -1 4 5 17 -1 3 16 15 -1 3 4 16 -1 2 15 14 -1 2 3 15 -1 1 14 13 -1 1 2 14 -1 0 1 12 -1 12 1 13 -1
621 | ]
622 | creaseAngle 1
623 | }
624 | }
625 | DEF LEFT_BOLT_SHAPE Shape {
626 | appearance PBRAppearance {
627 | baseColor 0.689949 0.689949 0.689949
628 | roughness 0.3
629 | }
630 | geometry IndexedFaceSet {
631 | coord Coordinate {
632 | point [
633 | -0.0230282 3.56e-05 -0.003356, -0.0230282 -0.0028886 -0.0017088 -0.0230282 -0.0029241 0.0016472, -0.0230282 -3.56e-05 0.003356 -0.0230282 0.0028886 0.0017088, -0.0230282 0.0029241 -0.0016472 -0.0249718 3.56e-05 -0.003356, -0.0249718 -0.0028886 -0.0017088 -0.0249718 -0.0029241 0.0016472, -0.0249718 -3.56e-05 0.003356 -0.0249718 0.0028886 0.0017088, -0.0249718 0.0029241 -0.0016472 -0.0249718 -0 -0
634 | ]
635 | }
636 | coordIndex [
637 | 12 6 7 -1 12 7 8 -1 12 8 9 -1 12 9 10 -1 12 10 11 -1 12 11 6 -1 0 1 7 6 -1 1 2 8 7 -1 2 3 9 8 -1 3 4 10 9 -1 4 5 11 10 -1 5 0 6 11 -1
638 | ]
639 | creaseAngle 1
640 | }
641 | }
642 | DEF RIM_SHAPE Shape {
643 | appearance PBRAppearance {
644 | baseColor 0.98 0.66 0.02
645 | metalness 0
646 | roughness 0.3
647 | }
648 | geometry IndexedFaceSet {
649 | coord Coordinate {
650 | point [
651 | 0.0231519 0 -0, 0.0231519 -0.0005683 0.0535874 0.0231519 -0.0144184 0.0516144, 0.0231519 -0.0272859 0.0461239 0.0231519 -0.0382939 0.0374902, 0.0231519 -0.0466922 0.0263015 0.0231519 -0.0060656 0.0184194, 0.0231519 -0.005971 0.0463876 0.0231519 -0.023339 0.0393337, 0.0231519 -0.0372792 0.0278663 0.0231519 -0.0128251 0.0144206, 0.0231519 0.0060761 0.0183172 0.0231519 0.0054933 0.0462179, 0.0231519 0.0223945 0.039879 0.0231519 0.0371873 0.0283648, 0.0231519 0.0129189 0.0144627 0.0231519 0.0133205 0.0519086, 0.0231519 0.0263015 0.0466923 0.0231519 0.0374902 0.0382939, 0.0231519 0.0461239 0.0272859 0.0231519 0.0519086 -0.0133205, 0.0231519 0.0535875 0.0005684 0.0231519 0.0516144 0.0144184, 0.0231519 0.0189845 -0.0039568 0.0231519 0.0431583 -0.0180228, 0.0231519 0.0457335 0.0005453 0.0231519 0.0427726 0.0183516, 0.0231519 0.0189012 0.0038966 0.0231519 0.0128251 -0.0144206, 0.0231519 0.0372793 -0.0278663 0.0231519 0.023339 -0.0393337, 0.0231519 0.005971 -0.0463876 0.0231519 0.0060656 -0.0184194, 0.0231519 0.0466923 -0.0263015 0.0231519 0.0382939 -0.0374902, 0.0231519 0.0272859 -0.0461239 0.0231519 0.0144184 -0.0516144, 0.0231519 -0.0461239 -0.0272859 0.0231519 -0.0374902 -0.0382939, 0.0231519 -0.0263015 -0.0466923 0.0231519 -0.0133205 -0.0519086, 0.0231519 0.0005684 -0.0535874 0.0231519 -0.0129189 -0.0144627, 0.0231519 -0.0371873 -0.0283648 0.0231519 -0.0223945 -0.039879, 0.0231519 -0.0054933 -0.0462179 0.0231519 -0.0060761 -0.0183172, 0.0231519 -0.0189012 -0.0038966 0.0231519 -0.0427725 -0.0183516, 0.0231519 -0.0457335 -0.0005453 0.0231519 -0.0431583 0.0180228, 0.0231519 -0.0189845 0.0039568 0.0231519 -0.0516144 -0.0144184, 0.0231519 -0.0535875 -0.0005684 0.0231519 -0.0519086 0.0133205, -0.0231519 -0.0519086 0.0133205 -0.0231519 -0.0535875 -0.0005684, -0.0231519 -0.0516144 -0.0144184 -0.0231519 -0.0189845 0.0039568, -0.0231519 -0.0431583 0.0180228 -0.0231519 -0.0457335 -0.0005453, -0.0231519 -0.0427725 -0.0183516 -0.0231519 -0.0189012 -0.0038966, -0.0231519 -0.0060761 -0.0183172 -0.0231519 -0.0054933 -0.0462179, -0.0231519 -0.0223945 -0.039879 -0.0231519 -0.0371873 -0.0283648, -0.0231519 -0.0129189 -0.0144627 -0.0231519 0.0005684 -0.0535874, -0.0231519 -0.0133205 -0.0519086 -0.0231519 -0.0263015 -0.0466923, -0.0231519 -0.0374902 -0.0382939 -0.0231519 -0.0461239 -0.0272859, -0.0231519 0.0144184 -0.0516144 -0.0231519 0.0272859 -0.0461239, -0.0231519 0.0382939 -0.0374902 -0.0231519 0.0466923 -0.0263015, -0.0231519 0.0060656 -0.0184194 -0.0231519 0.005971 -0.0463876, -0.0231519 0.023339 -0.0393337 -0.0231519 0.0372793 -0.0278663, -0.0231519 0.0128251 -0.0144206 -0.0231519 0.0189012 0.0038966, -0.0231519 0.0427726 0.0183516 -0.0231519 0.0457335 0.0005453, -0.0231519 0.0431583 -0.0180228 -0.0231519 0.0189845 -0.0039568, -0.0231519 0.0516144 0.0144184 -0.0231519 0.0535875 0.0005684, -0.0231519 0.0519086 -0.0133205 -0.0231519 0.0461239 0.0272859, -0.0231519 0.0374902 0.0382939 -0.0231519 0.0263015 0.0466923, -0.0231519 0.0133205 0.0519086 -0.0231519 0.0129189 0.0144627, -0.0231519 0.0371873 0.0283648 -0.0231519 0.0223945 0.039879, -0.0231519 0.0054933 0.0462179 -0.0231519 0.0060761 0.0183172, -0.0231519 -0.0128251 0.0144206 -0.0231519 -0.0372792 0.0278663, -0.0231519 -0.023339 0.0393337 -0.0231519 -0.005971 0.0463876, -0.0231519 -0.0060656 0.0184194 -0.0231519 -0.0466922 0.0263015, -0.0231519 -0.0382939 0.0374902 -0.0231519 -0.0272859 0.0461239, -0.0231519 -0.0144184 0.0516144 -0.0231519 -0.0005683 0.0535874, -0.0231519 0 -0
652 | ]
653 | }
654 | coordIndex [
655 | 0 6 10 -1 3 4 8 -1 2 3 8 -1 2 8 7 -1 1 2 7 -1 1 7 6 -1 0 1 6 -1 0 10 5 -1 5 10 9 -1 4 5 9 -1 4 9 8 -1 16 12 13 -1 16 1 12 -1 1 11 12 -1 0 11 1 -1 0 19 15 -1 19 14 15 -1 19 18 14 -1 18 13 14 -1 18 17 13 -1 17 16 13 -1 0 15 11 -1 0 23 27 -1 21 22 25 -1 20 21 25 -1 20 25 24 -1 33 20 24 -1 33 24 23 -1 0 33 23 -1 0 27 19 -1 19 27 26 -1 22 19 26 -1 22 26 25 -1 34 29 30 -1 34 33 29 -1 33 28 29 -1 0 28 33 -1 0 41 32 -1 41 31 32 -1 41 36 31 -1 36 30 31 -1 36 35 30 -1 35 34 30 -1 0 32 28 -1 0 42 46 -1 39 40 44 -1 38 39 44 -1 38 44 43 -1 37 38 43 -1 37 43 42 -1 0 37 42 -1 0 46 41 -1 41 46 45 -1 40 41 45 -1 40 45 44 -1 52 48 49 -1 52 37 48 -1 37 47 48 -1 0 47 37 -1 0 5 51 -1 5 50 51 -1 5 54 50 -1 54 49 50 -1 54 53 49 -1 53 52 49 -1 0 51 47 -1 99 103 109 -1 101 105 106 -1 101 106 107 -1 102 101 107 -1 102 107 108 -1 103 102 108 -1 103 108 109 -1 104 99 109 -1 100 99 104 -1 100 104 105 -1 101 100 105 -1 96 97 93 -1 97 108 93 -1 97 98 108 -1 108 98 109 -1 94 90 109 -1 94 95 90 -1 95 91 90 -1 95 96 91 -1 96 92 91 -1 96 93 92 -1 98 94 109 -1 82 86 109 -1 84 87 88 -1 84 88 89 -1 85 84 89 -1 85 89 76 -1 86 85 76 -1 86 76 109 -1 90 82 109 -1 83 82 90 -1 83 90 87 -1 84 83 87 -1 79 80 75 -1 80 76 75 -1 80 81 76 -1 76 81 109 -1 77 68 109 -1 77 78 68 -1 78 73 68 -1 78 79 73 -1 79 74 73 -1 79 75 74 -1 81 77 109 -1 63 67 109 -1 65 69 70 -1 65 70 71 -1 66 65 71 -1 66 71 72 -1 67 66 72 -1 67 72 109 -1 68 63 109 -1 64 63 68 -1 64 68 69 -1 65 64 69 -1 60 61 57 -1 61 72 57 -1 61 62 72 -1 72 62 109 -1 58 104 109 -1 58 59 104 -1 59 55 104 -1 59 60 55 -1 60 56 55 -1 60 57 56 -1 62 58 109 -1 3 2 107 -1 3 107 106 -1 4 3 106 -1 4 106 105 -1 5 4 105 -1 5 105 104 -1 8 9 100 -1 8 100 101 -1 9 10 99 -1 9 99 100 -1 6 7 102 -1 6 102 103 -1 7 8 101 -1 7 101 102 -1 10 6 103 -1 10 103 99 -1 2 1 108 -1 2 108 107 -1 18 19 90 -1 18 90 91 -1 11 15 94 -1 11 94 98 -1 14 13 96 -1 14 96 95 -1 15 14 95 -1 15 95 94 -1 12 11 98 -1 12 98 97 -1 13 12 97 -1 13 97 96 -1 16 17 92 -1 16 92 93 -1 17 18 91 -1 17 91 92 -1 21 20 89 -1 21 89 88 -1 22 21 88 -1 22 88 87 -1 25 26 83 -1 25 83 84 -1 26 27 82 -1 26 82 83 -1 23 24 85 -1 23 85 86 -1 24 25 84 -1 24 84 85 -1 27 23 86 -1 27 86 82 -1 28 32 77 -1 28 77 81 -1 31 30 79 -1 31 79 78 -1 32 31 78 -1 32 78 77 -1 29 28 81 -1 29 81 80 -1 30 29 80 -1 30 80 79 -1 33 34 75 -1 33 75 76 -1 34 35 74 -1 34 74 75 -1 35 36 73 -1 35 73 74 -1 39 38 71 -1 39 71 70 -1 40 39 70 -1 40 70 69 -1 41 40 69 -1 41 69 68 -1 44 45 64 -1 44 64 65 -1 45 46 63 -1 45 63 64 -1 42 43 66 -1 42 66 67 -1 43 44 65 -1 43 65 66 -1 46 42 67 -1 46 67 63 -1 38 37 72 -1 38 72 71 -1 47 51 58 -1 47 58 62 -1 50 49 60 -1 50 60 59 -1 51 50 59 -1 51 59 58 -1 48 47 62 -1 48 62 61 -1 49 48 61 -1 49 61 60 -1 52 53 56 -1 52 56 57 -1 53 54 55 -1 53 55 56 -1 37 52 57 -1 37 57 72 -1 54 5 104 -1 54 104 55 -1 36 41 68 -1 36 68 73 -1 20 33 76 -1 20 76 89 -1 19 22 87 -1 19 87 90 -1 1 16 93 -1 1 93 108 -1
656 | ]
657 | creaseAngle 1
658 | }
659 | }
660 | DEF TIRE_SHAPE Shape {
661 | appearance PBRAppearance {
662 | roughness 0.9
663 | metalness 0
664 | baseColorMap ImageTexture {
665 | url [
666 | "textures/smooth_rubber_base_color.jpg"
667 | ]
668 | }
669 | roughnessMap ImageTexture {
670 | url [
671 | "textures/smooth_rubber_roughness.jpg"
672 | ]
673 | }
674 | normalMap ImageTexture {
675 | url [
676 | "textures/smooth_rubber_normal.jpg"
677 | ]
678 | }
679 | occlusionMap ImageTexture {
680 | url [
681 | "textures/smooth_rubber_occlusion.jpg"
682 | ]
683 | }
684 | }
685 | geometry IndexedFaceSet {
686 | coord DEF coord_LEFT_TIRE Coordinate {
687 | point [
688 | -0.0215271 -0.0483949 -0.0135191, -0.0229106 -0.0684648 -0.0191256 -0.0187068 -0.0805348 -0.0224973, -0.0092433 -0.0881998 -0.0246385 -0.0014315 -0.0922773 -0.0257776, 0.0084399 -0.0881998 -0.0246385 0.0179033 -0.0805348 -0.0224973, 0.0229106 -0.0692388 -0.0193418 0.0211122 -0.0492123 -0.0137474, 0.0211122 -0.0510935 -0.0005419 0.0229106 -0.0718855 -0.0007624, 0.0179033 -0.0836134 -0.0008868 0.0084399 -0.0915714 -0.0009712, -0.0014315 -0.0958048 -0.0010161 -0.0092433 -0.0915714 -0.0009712, -0.0187068 -0.0836134 -0.0008868 -0.0229106 -0.071082 -0.0007539, -0.0215271 -0.0502449 -0.0005329 -0.0215271 -0.0486708 0.0124896, -0.0229106 -0.0688551 0.0176692 -0.0187068 -0.0809939 0.0207842, -0.0092433 -0.0887026 0.0227623 -0.0014315 -0.0928033 0.0238146, 0.0084399 -0.0887026 0.0227623 0.0179033 -0.0809939 0.0207842, 0.0229106 -0.0696334 0.0178689 0.0211122 -0.0494928 0.0127006, 0.0211122 -0.0445192 0.0250775 0.0229106 -0.0626359 0.0352825, 0.0179033 -0.0728548 0.0410387 0.0084399 -0.0797888 0.0449446, -0.0014315 -0.0834774 0.0470224 -0.0092433 -0.0797888 0.0449446, -0.0187068 -0.0728548 0.0410387 -0.0229106 -0.0619358 0.0348881, -0.0215271 -0.0437798 0.024661 -0.0215271 -0.0359053 0.0351517, -0.0229106 -0.0507957 0.0497295 -0.0187068 -0.0597507 0.0584966, -0.0092433 -0.0654375 0.064064 -0.0014315 -0.0684627 0.0670258, 0.0084399 -0.0654375 0.064064 0.0179033 -0.0597507 0.0584966, 0.0229106 -0.0513698 0.0502916 0.0211122 -0.0365118 0.0357454, 0.0211122 -0.0260161 0.0439774 0.0229106 -0.036603 0.0618735, 0.0179033 -0.0425747 0.071968 0.0084399 -0.0466268 0.0788176, -0.0014315 -0.0487824 0.0824614 -0.0092433 -0.0466268 0.0788176, -0.0187068 -0.0425747 0.071968 -0.0229106 -0.0361939 0.0611819, -0.0215271 -0.0255839 0.0432469 -0.0215271 -0.0135191 0.0483949, -0.0229106 -0.0191256 0.0684649 -0.0187068 -0.0224973 0.0805349, -0.0092433 -0.0246385 0.0881998 -0.0014315 -0.0257776 0.0922773, 0.0084399 -0.0246385 0.0881998 0.0179033 -0.0224973 0.0805349, 0.0229106 -0.0193418 0.0692388 0.0211122 -0.0137474 0.0492123, 0.0211122 -0.0005419 0.0510935 0.0229106 -0.0007624 0.0718855, 0.0179033 -0.0008868 0.0836134 0.0084399 -0.0009712 0.0915714, -0.0014315 -0.0010161 0.0958048 -0.0092433 -0.0009712 0.0915714, -0.0187068 -0.0008868 0.0836134 -0.0229106 -0.0007539 0.071082, -0.0215271 -0.0005329 0.0502449 -0.0215271 0.0124896 0.0486708, -0.0229106 0.0176692 0.0688551 -0.0187068 0.0207842 0.0809939, -0.0092433 0.0227623 0.0887025 -0.0014315 0.0238146 0.0928033, 0.0084399 0.0227623 0.0887025 0.0179033 0.0207842 0.0809939, 0.0229106 0.0178689 0.0696334 0.0211122 0.0127005 0.0494928, 0.0211122 0.0250775 0.0445192 0.0229106 0.0352825 0.0626359, 0.0179033 0.0410387 0.0728547 0.0084399 0.0449446 0.0797887, -0.0014315 0.0470224 0.0834774 -0.0092433 0.0449446 0.0797887, -0.0187068 0.0410387 0.0728547 -0.0229106 0.0348881 0.0619358, -0.0215271 0.0246609 0.0437798 -0.0215271 0.0351517 0.0359053, -0.0229106 0.0497295 0.0507956 -0.0187068 0.0584965 0.0597507, -0.0092433 0.064064 0.0654375 -0.0014315 0.0670257 0.0684627, 0.0084399 0.064064 0.0654375 0.0179033 0.0584965 0.0597507, 0.0229106 0.0502916 0.0513698 0.0211122 0.0357454 0.0365118, 0.0211122 0.0439773 0.0260161 0.0229106 0.0618735 0.036603, 0.0179033 0.0719679 0.0425747 0.0084399 0.0788175 0.0466268, -0.0014315 0.0824613 0.0487824 -0.0092433 0.0788175 0.0466268, -0.0187068 0.0719679 0.0425747 -0.0229106 0.0611819 0.0361939, -0.0215271 0.0432469 0.0255839 -0.0215271 0.0483949 0.0135191, -0.0229106 0.0684648 0.0191256 -0.0187068 0.0805348 0.0224973, -0.0092433 0.0881998 0.0246385 -0.0014315 0.0922773 0.0257776, 0.0084399 0.0881998 0.0246385 0.0179033 0.0805348 0.0224973, 0.0229106 0.0692387 0.0193418 0.0211122 0.0492123 0.0137474, 0.0211122 0.0510935 0.0005419 0.0229106 0.0718855 0.0007624, 0.0179033 0.0836134 0.0008868 0.0084399 0.0915714 0.0009712, -0.0014315 0.0958048 0.0010161 -0.0092433 0.0915714 0.0009712, -0.0187068 0.0836134 0.0008868 -0.0229106 0.071082 0.0007539, -0.0215271 0.0502449 0.0005329 -0.0215271 0.0486707 -0.0124896, -0.0229106 0.0688551 -0.0176692 -0.0187068 0.0809939 -0.0207842, -0.0092433 0.0887025 -0.0227623 -0.0014315 0.0928033 -0.0238146, 0.0084399 0.0887025 -0.0227623 0.0179033 0.0809939 -0.0207842, 0.0229106 0.0696334 -0.0178689 0.0211122 0.0494928 -0.0127005, 0.0211122 0.0445192 -0.0250775 0.0229106 0.0626359 -0.0352825, 0.0179033 0.0728547 -0.0410387 0.0084399 0.0797887 -0.0449446, -0.0014315 0.0834774 -0.0470224 -0.0092433 0.0797887 -0.0449446, -0.0187068 0.0728547 -0.0410387 -0.0229106 0.0619358 -0.0348881, -0.0215271 0.0437798 -0.0246609 -0.0215271 0.0359053 -0.0351517, -0.0229106 0.0507956 -0.0497295 -0.0187068 0.0597507 -0.0584966, -0.0092433 0.0654375 -0.064064 -0.0014315 0.0684627 -0.0670257, 0.0084399 0.0654375 -0.064064 0.0179033 0.0597507 -0.0584966, 0.0229106 0.0513698 -0.0502916 0.0211122 0.0365117 -0.0357454, 0.0211122 0.026016 -0.0439773 0.0229106 0.036603 -0.0618735, 0.0179033 0.0425747 -0.0719679 0.0084399 0.0466267 -0.0788175, -0.0014315 0.0487823 -0.0824613 -0.0092433 0.0466267 -0.0788175, -0.0187068 0.0425747 -0.0719679 -0.0229106 0.0361939 -0.0611819, -0.0215271 0.0255839 -0.0432469 -0.0215271 0.013519 -0.0483949, -0.0229106 0.0191255 -0.0684648 -0.0187068 0.0224973 -0.0805348, -0.0092433 0.0246385 -0.0881998 -0.0014315 0.0257775 -0.0922773, 0.0084399 0.0246385 -0.0881998 0.0179033 0.0224973 -0.0805348, 0.0229106 0.0193417 -0.0692387 0.0211122 0.0137474 -0.0492123, 0.0211122 0.0005419 -0.0510935 0.0229106 0.0007624 -0.0718855, 0.0179033 0.0008868 -0.0836134 0.0084399 0.0009712 -0.0915714, -0.0014315 0.0010161 -0.0958048 -0.0092433 0.0009712 -0.0915714, -0.0187068 0.0008868 -0.0836134 -0.0229106 0.0007538 -0.071082, -0.0215271 0.0005329 -0.0502449 -0.0215271 -0.0124896 -0.0486707, -0.0229106 -0.0176692 -0.068855 -0.0187068 -0.0207842 -0.0809939, -0.0092433 -0.0227624 -0.0887025 -0.0014315 -0.0238147 -0.0928033, 0.0084399 -0.0227624 -0.0887025 0.0179033 -0.0207842 -0.0809939, 0.0229106 -0.0178689 -0.0696333 0.0211122 -0.0127006 -0.0494928, 0.0211122 -0.0250775 -0.0445192 0.0229106 -0.0352825 -0.0626358, 0.0179033 -0.0410388 -0.0728547 0.0084399 -0.0449446 -0.0797887, -0.0014315 -0.0470225 -0.0834774 -0.0092433 -0.0449446 -0.0797887, -0.0187068 -0.0410388 -0.0728547 -0.0229106 -0.0348882 -0.0619357, -0.0215271 -0.024661 -0.0437798 -0.0215271 -0.0351517 -0.0359053, -0.0229106 -0.0497295 -0.0507956 -0.0187068 -0.0584966 -0.0597506, -0.0092433 -0.064064 -0.0654374 -0.0014315 -0.0670258 -0.0684627, 0.0084399 -0.064064 -0.0654374 0.0179033 -0.0584966 -0.0597506, 0.0229106 -0.0502916 -0.0513698 0.0211122 -0.0357454 -0.0365117, 0.0211122 -0.0439773 -0.026016 0.0229106 -0.0618735 -0.036603, 0.0179033 -0.071968 -0.0425747 0.0084399 -0.0788176 -0.0466267, -0.0014315 -0.0824614 -0.0487823 -0.0092433 -0.0788176 -0.0466267, -0.0187068 -0.071968 -0.0425747 -0.0229106 -0.0611819 -0.0361938, -0.0215271 -0.0432469 -0.0255839
689 | ]
690 | }
691 | texCoord TextureCoordinate {
692 | point [
693 | 0.64703 -2.70087, 0.52606 -2.70539, 0.52606 -3.21748 0.64703 -3.21301, 0.233719 0.933134, 0.233749 0.934086 0.2339 0.93409, 0.233933 0.93314, 0.981635 -2.68407 0.782565 -2.69496, 0.782565 -3.20449, 0.981635 -3.19048 0.782565 -2.69496, 0.64703 -2.70087, 0.64703 -3.21301 0.782565 -3.20449, 0.52606 -2.70539, 0.378934 -2.71083 0.378934 -3.22505, 0.52606 -3.21748, 0.378934 -2.71083 0.214863 -2.71749, 0.214863 -3.23143, 0.378934 -3.22505 0.214863 -2.71749, 0.027927 -2.72369, 0.027927 -3.23817 0.214863 -3.23143, 0.2323 0.939706, 0.232267 0.938756 0.232114 0.93876, 0.232084 0.939711, 0.232084 0.939711 0.232114 0.93876, 0.231966 0.938606, 0.231876 0.939494 0.214863 -3.23143, 0.027927 -3.23817, 0.027927 -3.7638 0.214863 -3.75321, 0.378934 -3.22505, 0.214863 -3.23143 0.214863 -3.75321, 0.378934 -3.74407, 0.52606 -3.21748 0.378934 -3.22505, 0.378934 -3.74407, 0.52606 -3.73485 0.782565 -3.20449, 0.64703 -3.21301, 0.64703 -3.72922 0.782565 -3.71864, 0.981635 -3.19048, 0.782565 -3.20449 0.782565 -3.71864, 0.981635 -3.70308, 0.233749 0.934086 0.233719 0.933134, 0.233513 0.933349, 0.233603 0.934238 0.64703 -3.21301, 0.52606 -3.21748, 0.52606 -3.73485 0.64703 -3.72922, 0.64703 -3.72922, 0.52606 -3.73485 0.52606 -4.25611, 0.64703 -4.24832, 0.233603 0.934238 0.233513 0.933349, 0.233328 0.933769, 0.233472 0.934535 0.981635 -3.70308, 0.782565 -3.71864, 0.782565 -4.23643 0.981635 -4.21985, 0.782565 -3.71864, 0.64703 -3.72922 0.64703 -4.24832, 0.782565 -4.23643, 0.52606 -3.73485 0.378934 -3.74407, 0.378934 -4.26449, 0.52606 -4.25611 0.378934 -3.74407, 0.214863 -3.75321, 0.214863 -4.27439 0.378934 -4.26449, 0.214863 -3.75321, 0.027927 -3.7638 0.027927 -4.28529, 0.214863 -4.27439, 0.231876 0.939494 0.231966 0.938606, 0.231833 0.938303, 0.231688 0.939069 0.231688 0.939069, 0.231833 0.938303, 0.231723 0.937874 0.231535 0.938465, 0.214863 -4.27439, 0.027927 -4.28529 0.027927 -4.80288, 0.214863 -4.79703, 0.378934 -4.26449 0.214863 -4.27439, 0.214863 -4.79703, 0.378934 -4.78924 0.52606 -4.25611, 0.378934 -4.26449, 0.378934 -4.78924 0.52606 -4.78189, 0.782565 -4.23643, 0.64703 -4.24832 0.64703 -4.77023, 0.782565 -4.75228, 0.981635 -4.21985 0.782565 -4.23643, 0.782565 -4.75228, 0.981635 -4.726 0.233472 0.934535, 0.233328 0.933769, 0.233176 0.934366 0.233365 0.934957, 0.64703 -4.24832, 0.52606 -4.25611 0.52606 -4.78189, 0.64703 -4.77023, 0.64703 -4.77023 0.52606 -4.78189, 0.52606 -5.3258, 0.64703 -5.30794 0.233365 0.934957, 0.233176 0.934366, 0.233068 0.9351 0.233288 0.935476, 0.981635 -4.726, 0.782565 -4.75228 0.782565 -5.27391, 0.981635 -5.22266, 0.782565 -4.75228 0.64703 -4.77023, 0.64703 -5.30794, 0.782565 -5.27391 0.52606 -4.78189, 0.378934 -4.78924, 0.378934 -5.3318 0.52606 -5.3258, 0.378934 -4.78924, 0.214863 -4.79703 0.214863 -5.33006, 0.378934 -5.3318, 0.214863 -4.79703 0.027927 -4.80288, 0.027927 -5.31756, 0.214863 -5.33006 0.231535 0.938465, 0.231723 0.937874, 0.231646 0.937347 0.231425 0.937723, 0.231425 0.937723, 0.231646 0.937347 0.231604 0.936757, 0.231367 0.936892, 0.214863 -5.33006 0.027927 -5.31756, 0.027927 -5.81961, 0.214863 -5.89036 0.378934 -5.3318, 0.214863 -5.33006, 0.214863 -5.89036 0.378934 -5.93545, 0.52606 -5.3258, 0.378934 -5.3318 0.378934 -5.93545, 0.52606 -5.93879, 0.782565 -5.27391 0.64703 -5.30794, 0.64703 -5.90266, 0.782565 -5.81934 0.981635 -5.22266, 0.782565 -5.27391, 0.782565 -5.81934 0.981635 -5.70447, 0.233288 0.935476, 0.233068 0.9351 0.233011 0.935921, 0.233248 0.936056, 0.64703 -5.30794 0.52606 -5.3258, 0.52606 -5.93879, 0.64703 -5.90266 0.64703 6.89384, 0.52606 6.93098, 0.52606 6.28051 0.64703 6.26729, 0.233247 0.936088, 0.233009 0.935966 0.23301 0.936819, 0.233247 0.93669, 0.981635 6.70188 0.782565 6.81596, 0.782565 6.2334, 0.981635 6.1825 0.782565 6.81596, 0.64703 6.89384, 0.64703 6.26729 0.782565 6.2334, 0.52606 6.93098, 0.378934 6.91981 0.378934 6.28987, 0.52606 6.28051, 0.378934 6.91981 0.214863 6.87494, 0.214863 6.28463, 0.378934 6.28987 0.214863 6.87494, 0.027927 6.80131, 0.027927 6.26849 0.214863 6.28463, 0.231365 0.936815, 0.231603 0.936702 0.231604 0.936089, 0.231367 0.935953, 0.231367 0.935953 0.231604 0.936089, 0.231646 0.935499, 0.231425 0.935123 0.214863 6.28463, 0.027927 6.26849, 0.027927 5.73306 0.214863 5.72814, 0.378934 6.28987, 0.214863 6.28463 0.214863 5.72814, 0.378934 5.723, 0.52606 6.28051 0.378934 6.28987, 0.378934 5.723, 0.52606 5.71222 0.782565 6.2334, 0.64703 6.26729, 0.64703 5.70304 0.782565 5.68251, 0.981635 6.1825, 0.782565 6.2334 0.782565 5.68251, 0.981635 5.65664, 0.233247 0.93669 0.23301 0.936819, 0.233065 0.937641, 0.233287 0.937272 0.64703 6.26729, 0.52606 6.28051, 0.52606 5.71222 0.64703 5.70304, 0.64703 5.70304, 0.52606 5.71222 0.52606 5.1687, 0.64703 5.16023, 0.233287 0.937272 0.233065 0.937641, 0.233172 0.938378, 0.233362 0.937793 0.981635 5.65664, 0.782565 5.68251, 0.782565 5.14501 0.981635 5.12858, 0.782565 5.68251, 0.64703 5.70304 0.64703 5.16023, 0.782565 5.14501, 0.52606 5.71222 0.378934 5.723, 0.378934 5.17786, 0.52606 5.1687 0.378934 5.723, 0.214863 5.72814, 0.214863 5.18555 0.378934 5.17786, 0.214863 5.72814, 0.027927 5.73306 0.027927 5.19647, 0.214863 5.18555, 0.231425 0.935123 0.231646 0.935499, 0.231723 0.934972, 0.231535 0.934381 0.231535 0.934381, 0.231723 0.934972, 0.231833 0.934542 0.231688 0.933777, 0.214863 5.18555, 0.027927 5.19647 0.027927 4.66287, 0.214863 4.65051, 0.378934 5.17786 0.214863 5.18555, 0.214863 4.65051, 0.378934 4.6427 0.52606 5.1687, 0.378934 5.17786, 0.378934 4.6427 0.52606 4.63514, 0.782565 5.14501, 0.64703 5.16023 0.64703 4.6276, 0.782565 4.61504, 0.981635 5.12858 0.782565 5.14501, 0.782565 4.61504, 0.981635 4.60345 0.233362 0.937793, 0.233172 0.938378, 0.233323 0.93898 0.233469 0.938218, 0.64703 5.16023, 0.52606 5.1687 0.52606 4.63514, 0.64703 4.6276, 0.64703 4.6276 0.52606 4.63514, 0.52606 4.10489, 0.64703 4.09987 0.233469 0.938218, 0.233323 0.93898, 0.233508 0.939405 0.233599 0.938519, 0.981635 4.60345, 0.782565 4.61504 0.782565 4.0898, 0.981635 4.08207, 0.782565 4.61504 0.64703 4.6276, 0.64703 4.09987, 0.782565 4.0898 0.52606 4.63514, 0.378934 4.6427, 0.378934 4.11339 0.52606 4.10489, 0.378934 4.6427, 0.214863 4.65051 0.214863 4.12064, 0.378934 4.11339, 0.214863 4.65051 0.027927 4.66287, 0.027927 4.13332, 0.214863 4.12064 0.231688 0.933777, 0.231833 0.934542, 0.231966 0.93424 0.231876 0.933352, 0.231876 0.933352, 0.231966 0.93424 0.232114 0.934086, 0.232084 0.933134, 0.214863 4.12064 0.027927 4.13332, 0.027927 3.60414, 0.214863 3.59179 0.378934 4.11339, 0.214863 4.12064, 0.214863 3.59179 0.378934 3.58532, 0.52606 4.10489, 0.378934 4.11339 0.378934 3.58532, 0.52606 3.57778, 0.782565 4.0898 0.64703 4.09987, 0.64703 3.57374, 0.782565 3.56561 0.981635 4.08207, 0.782565 4.0898, 0.782565 3.56561 0.981635 3.56088, 0.233599 0.938519, 0.233508 0.939405 0.233714 0.939625, 0.233745 0.938674, 0.64703 4.09987 0.52606 4.10489, 0.52606 3.57778, 0.64703 3.57374 0.64703 3.57374, 0.52606 3.57778, 0.52606 3.05141 0.64703 3.04831, 0.233745 0.938674, 0.233714 0.939625 0.233927 0.939625, 0.233896 0.938674, 0.981635 3.56088 0.782565 3.56561, 0.782565 3.04176, 0.981635 3.03923 0.782565 3.56561, 0.64703 3.57374, 0.64703 3.04831 0.782565 3.04176, 0.52606 3.57778, 0.378934 3.58532 0.378934 3.0579, 0.52606 3.05141, 0.378934 3.58532 0.214863 3.59179, 0.214863 3.06325, 0.378934 3.0579 0.214863 3.59179, 0.027927 3.60414, 0.027927 3.07457 0.214863 3.06325, 0.232084 0.933134, 0.232114 0.934086 0.232267 0.934089, 0.2323 0.93314, 0.2323 0.93314 0.232267 0.934089, 0.232415 0.934251, 0.232508 0.933367 0.214863 3.06325, 0.027927 3.07457, 0.027927 2.54448 0.214863 2.53454, 0.378934 3.0579, 0.214863 3.06325 0.214863 2.53454, 0.378934 2.53045, 0.52606 3.05141 0.378934 3.0579, 0.378934 2.53045, 0.52606 2.52504 0.782565 3.04176, 0.64703 3.04831, 0.64703 2.52287 0.782565 2.51775, 0.981635 3.03923, 0.782565 3.04176 0.782565 2.51775, 0.981635 2.51707, 0.233896 0.938674 0.233927 0.939625, 0.234133 0.939405, 0.234041 0.938519 0.64703 3.04831, 0.52606 3.05141, 0.52606 2.52504 0.64703 2.52287, 0.64703 2.52287, 0.52606 2.52504 0.52606 1.99839, 0.64703 1.99714, 0.234041 0.938519 0.234133 0.939405, 0.234317 0.93898, 0.234172 0.938218 0.981635 2.51707, 0.782565 2.51775, 0.782565 1.99338 0.981635 1.9944, 0.782565 2.51775, 0.64703 2.52287 0.64703 1.99714, 0.782565 1.99338, 0.52606 2.52504 0.378934 2.53045, 0.378934 2.00271, 0.52606 1.99839 0.378934 2.53045, 0.214863 2.53454, 0.214863 2.00548 0.378934 2.00271, 0.214863 2.53454, 0.027927 2.54448 0.027927 2.0139, 0.214863 2.00548, 0.232508 0.933367 0.232415 0.934251, 0.232547 0.934559, 0.232694 0.933801 0.232694 0.933801, 0.232547 0.934559, 0.232655 0.934993 0.232846 0.934412, 0.214863 2.00548, 0.027927 2.0139 0.027927 1.48284, 0.214863 1.47601, 0.378934 2.00271 0.214863 2.00548, 0.214863 1.47601, 0.378934 1.47461 0.52606 1.99839, 0.378934 2.00271, 0.378934 1.47461 0.52606 1.4714, 0.782565 1.99338, 0.64703 1.99714 0.64703 1.47104, 0.782565 1.46861, 0.981635 1.9944 0.782565 1.99338, 0.782565 1.46861, 0.981635 1.47125 0.234172 0.938218, 0.234317 0.93898, 0.234468 0.938378 0.234278 0.937793, 0.64703 1.99714, 0.52606 1.99839 0.52606 1.4714, 0.64703 1.47104, 0.64703 1.47104 0.52606 1.4714, 0.52606 0.947398, 0.64703 0.947398 0.234278 0.937793, 0.234468 0.938378, 0.234575 0.937641 0.234354 0.937272, 0.981635 1.47125, 0.782565 1.46861 0.782565 0.947398, 0.981635 0.947398, 0.782565 1.46861 0.64703 1.47104, 0.64703 0.947398, 0.782565 0.947398 0.52606 1.4714, 0.378934 1.47461, 0.378934 0.947398 0.52606 0.947398, 0.378934 1.47461, 0.214863 1.47601 0.214863 0.947398, 0.378934 0.947398, 0.214863 1.47601 0.027927 1.48284, 0.027927 0.947398, 0.214863 0.947398 0.232846 0.934412, 0.232655 0.934993, 0.232732 0.935525 0.232953 0.935159, 0.232953 0.935159, 0.232732 0.935525 0.232771 0.936117, 0.233009 0.935992, 0.214863 0.947398 0.027927 0.947398, 0.027927 0.419828, 0.214863 0.419828 0.378934 0.947398, 0.214863 0.947398, 0.214863 0.419828 0.378934 0.419828, 0.52606 0.947398, 0.378934 0.947398 0.378934 0.419828, 0.52606 0.419828, 0.782565 0.947398 0.64703 0.947398, 0.64703 0.419828, 0.782565 0.419828 0.981635 0.947398, 0.782565 0.947398, 0.782565 0.419828 0.981635 0.419828, 0.234354 0.937272, 0.234575 0.937641 0.234631 0.936819, 0.234393 0.93669, 0.64703 0.947398 0.52606 0.947398, 0.52606 0.419828, 0.64703 0.419828 0.64703 0.419828, 0.52606 0.419828, 0.52606 -0.110411 0.64703 -0.108206, 0.234393 0.93669, 0.234631 0.936819 0.234632 0.935967, 0.234394 0.936088, 0.981635 0.419828 0.782565 0.419828, 0.782565 -0.107376, 0.981635 -0.101107 0.782565 0.419828, 0.64703 0.419828, 0.64703 -0.108206 0.782565 -0.107376, 0.52606 0.419828, 0.378934 0.419828 0.378934 -0.110512, 0.52606 -0.110411, 0.378934 0.419828 0.214863 0.419828, 0.214863 -0.113676, 0.378934 -0.110512 0.214863 0.419828, 0.027927 0.419828, 0.027927 -0.112642 0.214863 -0.113676, 0.233009 0.935992, 0.232771 0.936117 0.232771 0.936729, 0.233009 0.936854, 0.233009 0.936854 0.232771 0.936729, 0.232732 0.937321, 0.232953 0.937687 0.214863 -0.113676, 0.027927 -0.112642, 0.027927 -0.635046 0.214863 -0.635046, 0.378934 -0.110512, 0.214863 -0.113676 0.214863 -0.635046, 0.378934 -0.635046, 0.52606 -0.110411 0.378934 -0.110512, 0.378934 -0.635046, 0.52606 -0.635046 0.782565 -0.107376, 0.64703 -0.108206, 0.64703 -0.635046 0.782565 -0.635046, 0.981635 -0.101107, 0.782565 -0.107376 0.782565 -0.635046, 0.981635 -0.635046, 0.234394 0.936088 0.234632 0.935967, 0.234577 0.935142, 0.234355 0.935505 0.64703 -0.108206, 0.52606 -0.110411, 0.52606 -0.635046 0.64703 -0.635046, 0.64703 -0.635046, 0.52606 -0.635046 0.52606 -1.15816, 0.64703 -1.15654, 0.234355 0.935505 0.234577 0.935142, 0.234472 0.934402, 0.234281 0.934982 0.981635 -0.635046, 0.782565 -0.635046, 0.782565 -1.15413 0.981635 -1.14773, 0.782565 -0.635046, 0.64703 -0.635046 0.64703 -1.15654, 0.782565 -1.15413, 0.52606 -0.635046 0.378934 -0.635046, 0.378934 -1.16204, 0.52606 -1.15816 0.378934 -0.635046, 0.214863 -0.635046, 0.214863 -1.16864 0.378934 -1.16204, 0.214863 -0.635046, 0.027927 -0.635046 0.027927 -1.17321, 0.214863 -1.16864, 0.232953 0.937687 0.232732 0.937321, 0.232655 0.937852, 0.232846 0.938434 0.232846 0.938434, 0.232655 0.937852, 0.232547 0.938287 0.232694 0.939045, 0.214863 -1.16864, 0.027927 -1.17321 0.027927 -1.6957, 0.214863 -1.68973, 0.378934 -1.16204 0.214863 -1.16864, 0.214863 -1.68973, 0.378934 -1.68209 0.52606 -1.15816, 0.378934 -1.16204, 0.378934 -1.68209 0.52606 -1.67724, 0.782565 -1.15413, 0.64703 -1.15654 0.64703 -1.67416, 0.782565 -1.67084, 0.981635 -1.14773 0.782565 -1.15413, 0.782565 -1.67084, 0.981635 -1.66291 0.234281 0.934982, 0.234472 0.934402, 0.234322 0.933797 0.234175 0.934554, 0.64703 -1.15654, 0.52606 -1.15816 0.52606 -1.67724, 0.64703 -1.67416, 0.64703 -1.67416 0.52606 -1.67724, 0.52606 -2.19295, 0.64703 -2.19295 0.234175 0.934554, 0.234322 0.933797, 0.234138 0.933366 0.234045 0.93425, 0.981635 -1.66291, 0.782565 -1.67084 0.782565 -2.19295, 0.981635 -2.19295, 0.782565 -1.67084 0.64703 -1.67416, 0.64703 -2.19295, 0.782565 -2.19295 0.52606 -1.67724, 0.378934 -1.68209, 0.378934 -2.19295 0.52606 -2.19295, 0.378934 -1.68209, 0.214863 -1.68973 0.214863 -2.19295, 0.378934 -2.19295, 0.214863 -1.68973 0.027927 -1.6957, 0.027927 -2.19295, 0.214863 -2.19295 0.232694 0.939045, 0.232547 0.938287, 0.232415 0.938595 0.232508 0.939479, 0.232508 0.939479, 0.232415 0.938595 0.232267 0.938756, 0.2323 0.939706, 0.214863 -2.19295 0.027927 -2.19295, 0.027927 -2.72369, 0.214863 -2.71749 0.378934 -2.19295, 0.214863 -2.19295, 0.214863 -2.71749 0.378934 -2.71083, 0.52606 -2.19295, 0.378934 -2.19295 0.378934 -2.71083, 0.52606 -2.70539, 0.782565 -2.19295 0.64703 -2.19295, 0.64703 -2.70087, 0.782565 -2.69496 0.981635 -2.19295, 0.782565 -2.19295, 0.782565 -2.69496 0.981635 -2.68407, 0.234045 0.93425, 0.234138 0.933366 0.233933 0.93314, 0.2339 0.93409, 0.64703 -2.19295 0.52606 -2.19295, 0.52606 -2.70539, 0.64703 -2.70087
694 | ]
695 | }
696 | coordIndex [
697 | 212 211 4 3 -1 1 0 215 214 -1 214 213 2 1 -1 213 212 3 2 -1 211 210 5 4 -1 210 209 6 5 -1 209 208 7 6 -1 208 207 8 7 -1 7 8 9 10 -1 6 7 10 11 -1 5 6 11 12 -1 4 5 12 13 -1 2 3 14 15 -1 1 2 15 16 -1 0 1 16 17 -1 3 4 13 14 -1 14 13 22 21 -1 17 16 19 18 -1 16 15 20 19 -1 15 14 21 20 -1 13 12 23 22 -1 12 11 24 23 -1 11 10 25 24 -1 10 9 26 25 -1 25 26 27 28 -1 24 25 28 29 -1 23 24 29 30 -1 22 23 30 31 -1 20 21 32 33 -1 19 20 33 34 -1 18 19 34 35 -1 21 22 31 32 -1 32 31 40 39 -1 35 34 37 36 -1 34 33 38 37 -1 33 32 39 38 -1 31 30 41 40 -1 30 29 42 41 -1 29 28 43 42 -1 28 27 44 43 -1 43 44 45 46 -1 42 43 46 47 -1 41 42 47 48 -1 40 41 48 49 -1 38 39 50 51 -1 37 38 51 52 -1 36 37 52 53 -1 39 40 49 50 -1 50 49 58 57 -1 53 52 55 54 -1 52 51 56 55 -1 51 50 57 56 -1 49 48 59 58 -1 48 47 60 59 -1 47 46 61 60 -1 46 45 62 61 -1 61 62 63 64 -1 60 61 64 65 -1 59 60 65 66 -1 58 59 66 67 -1 56 57 68 69 -1 55 56 69 70 -1 54 55 70 71 -1 57 58 67 68 -1 68 67 76 75 -1 71 70 73 72 -1 70 69 74 73 -1 69 68 75 74 -1 67 66 77 76 -1 66 65 78 77 -1 65 64 79 78 -1 64 63 80 79 -1 79 80 81 82 -1 78 79 82 83 -1 77 78 83 84 -1 76 77 84 85 -1 74 75 86 87 -1 73 74 87 88 -1 72 73 88 89 -1 75 76 85 86 -1 86 85 94 93 -1 89 88 91 90 -1 88 87 92 91 -1 87 86 93 92 -1 85 84 95 94 -1 84 83 96 95 -1 83 82 97 96 -1 82 81 98 97 -1 97 98 99 100 -1 96 97 100 101 -1 95 96 101 102 -1 94 95 102 103 -1 92 93 104 105 -1 91 92 105 106 -1 90 91 106 107 -1 93 94 103 104 -1 104 103 112 111 -1 107 106 109 108 -1 106 105 110 109 -1 105 104 111 110 -1 103 102 113 112 -1 102 101 114 113 -1 101 100 115 114 -1 100 99 116 115 -1 115 116 117 118 -1 114 115 118 119 -1 113 114 119 120 -1 112 113 120 121 -1 110 111 122 123 -1 109 110 123 124 -1 108 109 124 125 -1 111 112 121 122 -1 122 121 130 129 -1 125 124 127 126 -1 124 123 128 127 -1 123 122 129 128 -1 121 120 131 130 -1 120 119 132 131 -1 119 118 133 132 -1 118 117 134 133 -1 133 134 135 136 -1 132 133 136 137 -1 131 132 137 138 -1 130 131 138 139 -1 128 129 140 141 -1 127 128 141 142 -1 126 127 142 143 -1 129 130 139 140 -1 140 139 148 147 -1 143 142 145 144 -1 142 141 146 145 -1 141 140 147 146 -1 139 138 149 148 -1 138 137 150 149 -1 137 136 151 150 -1 136 135 152 151 -1 151 152 153 154 -1 150 151 154 155 -1 149 150 155 156 -1 148 149 156 157 -1 146 147 158 159 -1 145 146 159 160 -1 144 145 160 161 -1 147 148 157 158 -1 158 157 166 165 -1 161 160 163 162 -1 160 159 164 163 -1 159 158 165 164 -1 157 156 167 166 -1 156 155 168 167 -1 155 154 169 168 -1 154 153 170 169 -1 169 170 171 172 -1 168 169 172 173 -1 167 168 173 174 -1 166 167 174 175 -1 164 165 176 177 -1 163 164 177 178 -1 162 163 178 179 -1 165 166 175 176 -1 176 175 184 183 -1 179 178 181 180 -1 178 177 182 181 -1 177 176 183 182 -1 175 174 185 184 -1 174 173 186 185 -1 173 172 187 186 -1 172 171 188 187 -1 187 188 189 190 -1 186 187 190 191 -1 185 186 191 192 -1 184 185 192 193 -1 182 183 194 195 -1 181 182 195 196 -1 180 181 196 197 -1 183 184 193 194 -1 194 193 202 201 -1 197 196 199 198 -1 196 195 200 199 -1 195 194 201 200 -1 193 192 203 202 -1 192 191 204 203 -1 191 190 205 204 -1 190 189 206 205 -1 205 206 207 208 -1 204 205 208 209 -1 203 204 209 210 -1 202 203 210 211 -1 200 201 212 213 -1 199 200 213 214 -1 198 199 214 215 -1 201 202 211 212 -1
698 | ]
699 | texCoordIndex [
700 | 0 1 2 3 -1 4 5 6 7 -1 8 9 10 11 -1 12 13 14 15 -1 16 17 18 19 -1 20 21 22 23 -1 24 25 26 27 -1 28 29 30 31 -1 32 33 34 35 -1 36 37 38 39 -1 40 41 42 43 -1 44 45 46 47 -1 48 49 50 51 -1 52 53 54 55 -1 56 57 58 59 -1 60 61 62 63 -1 64 65 66 67 -1 68 69 70 71 -1 72 73 74 75 -1 76 77 78 79 -1 80 81 82 83 -1 84 85 86 87 -1 88 89 90 91 -1 92 93 94 95 -1 96 97 98 99 -1 100 101 102 103 -1 104 105 106 107 -1 108 109 110 111 -1 112 113 114 115 -1 116 117 118 119 -1 120 121 122 123 -1 124 125 126 127 -1 128 129 130 131 -1 132 133 134 135 -1 136 137 138 139 -1 140 141 142 143 -1 144 145 146 147 -1 148 149 150 151 -1 152 153 154 155 -1 156 157 158 159 -1 160 161 162 163 -1 164 165 166 167 -1 168 169 170 171 -1 172 173 174 175 -1 176 177 178 179 -1 180 181 182 183 -1 184 185 186 187 -1 188 189 190 191 -1 192 193 194 195 -1 196 197 198 199 -1 200 201 202 203 -1 204 205 206 207 -1 208 209 210 211 -1 212 213 214 215 -1 216 217 218 219 -1 220 221 222 223 -1 224 225 226 227 -1 228 229 230 231 -1 232 233 234 235 -1 236 237 238 239 -1 240 241 242 243 -1 244 245 246 247 -1 248 249 250 251 -1 252 253 254 255 -1 256 257 258 259 -1 260 261 262 263 -1 264 265 266 267 -1 268 269 270 271 -1 272 273 274 275 -1 276 277 278 279 -1 280 281 282 283 -1 284 285 286 287 -1 288 289 290 291 -1 292 293 294 295 -1 296 297 298 299 -1 300 301 302 303 -1 304 305 306 307 -1 308 309 310 311 -1 312 313 314 315 -1 316 317 318 319 -1 320 321 322 323 -1 324 325 326 327 -1 328 329 330 331 -1 332 333 334 335 -1 336 337 338 339 -1 340 341 342 343 -1 344 345 346 347 -1 348 349 350 351 -1 352 353 354 355 -1 356 357 358 359 -1 360 361 362 363 -1 364 365 366 367 -1 368 369 370 371 -1 372 373 374 375 -1 376 377 378 379 -1 380 381 382 383 -1 384 385 386 387 -1 388 389 390 391 -1 392 393 394 395 -1 396 397 398 399 -1 400 401 402 403 -1 404 405 406 407 -1 408 409 410 411 -1 412 413 414 415 -1 416 417 418 419 -1 420 421 422 423 -1 424 425 426 427 -1 428 429 430 431 -1 432 433 434 435 -1 436 437 438 439 -1 440 441 442 443 -1 444 445 446 447 -1 448 449 450 451 -1 452 453 454 455 -1 456 457 458 459 -1 460 461 462 463 -1 464 465 466 467 -1 468 469 470 471 -1 472 473 474 475 -1 476 477 478 479 -1 480 481 482 483 -1 484 485 486 487 -1 488 489 490 491 -1 492 493 494 495 -1 496 497 498 499 -1 500 501 502 503 -1 504 505 506 507 -1 508 509 510 511 -1 512 513 514 515 -1 516 517 518 519 -1 520 521 522 523 -1 524 525 526 527 -1 528 529 530 531 -1 532 533 534 535 -1 536 537 538 539 -1 540 541 542 543 -1 544 545 546 547 -1 548 549 550 551 -1 552 553 554 555 -1 556 557 558 559 -1 560 561 562 563 -1 564 565 566 567 -1 568 569 570 571 -1 572 573 574 575 -1 576 577 578 579 -1 580 581 582 583 -1 584 585 586 587 -1 588 589 590 591 -1 592 593 594 595 -1 596 597 598 599 -1 600 601 602 603 -1 604 605 606 607 -1 608 609 610 611 -1 612 613 614 615 -1 616 617 618 619 -1 620 621 622 623 -1 624 625 626 627 -1 628 629 630 631 -1 632 633 634 635 -1 636 637 638 639 -1 640 641 642 643 -1 644 645 646 647 -1 648 649 650 651 -1 652 653 654 655 -1 656 657 658 659 -1 660 661 662 663 -1 664 665 666 667 -1 668 669 670 671 -1 672 673 674 675 -1 676 677 678 679 -1 680 681 682 683 -1 684 685 686 687 -1 688 689 690 691 -1 692 693 694 695 -1 696 697 698 699 -1 700 701 702 703 -1 704 705 706 707 -1 708 709 710 711 -1 712 713 714 715 -1 716 717 718 719 -1 720 721 722 723 -1 724 725 726 727 -1 728 729 730 731 -1 732 733 734 735 -1 736 737 738 739 -1 740 741 742 743 -1 744 745 746 747 -1 748 749 750 751 -1 752 753 754 755 -1 756 757 758 759 -1 760 761 762 763 -1 764 765 766 767 -1
701 | ]
702 | creaseAngle 1
703 | }
704 | }
705 | ]
706 | name "left wheel"
707 | boundingObject DEF BOUNDING_WHEEL Group {
708 | children [
709 | Transform {
710 | rotation 0 0 1 1.5708
711 | children [
712 | Cylinder {
713 | height 0.01
714 | radius 0.0975
715 | subdivision 32
716 | }
717 | ]
718 | }
719 | Transform {
720 | rotation 0 0 1 1.5708
721 | children [
722 | Cylinder {
723 | height 0.048
724 | radius 0.07
725 | subdivision 24
726 | }
727 | ]
728 | }
729 | ]
730 | }
731 | physics Physics {
732 | }
733 | }
734 | }
735 | DEF LOWER_YELLOW_LED LED {
736 | translation -0.130063 0.0922878 0.0531755
737 | rotation 1 0 0 0
738 | children [
739 | DEF YELLOW_LED_SHAPE Shape {
740 | appearance PBRAppearance {
741 | baseColor 0.973226 0.749467 0.19481
742 | transparency 0.395718
743 | metalness 0
744 | roughness 0.3
745 | }
746 | geometry USE LED_SHAPE
747 | }
748 | ]
749 | name "lower yellow led"
750 | color [
751 | 0.976471 0.980392 0.603922
752 | ]
753 | }
754 | DEF RED_LED_1 LED {
755 | translation -0.130137 0.0802345 0.0924989
756 | rotation 1 0 0 0
757 | children [
758 | DEF RED_LED_SHAPE Group {
759 | children [
760 | Shape {
761 | appearance PBRAppearance {
762 | baseColor 1 0 0
763 | metalness 0
764 | roughness 0.3
765 | transparency 0.395718
766 | }
767 | geometry USE LED_SHAPE
768 | }
769 | PointLight {
770 | attenuation 0 0 1
771 | color 0 0 0
772 | intensity 0.003
773 | location -0.02 0 0
774 | }
775 | ]
776 | }
777 | ]
778 | name "red led 1"
779 | color [
780 | 0.913725 0.247059 0.247059
781 | ]
782 | }
783 | DEF RED_LED_2 LED {
784 | translation -0.130137 0.0802345 0.0635791
785 | rotation 1 0 0 0
786 | children [
787 | DEF RED_LED_SHAPE Group {
788 | children [
789 | Shape {
790 | appearance PBRAppearance {
791 | baseColor 1 0 0
792 | metalness 0
793 | roughness 0.3
794 | transparency 0.395718
795 | }
796 | geometry USE LED_SHAPE
797 | }
798 | ]
799 | }
800 | ]
801 | name "red led 2"
802 | color [
803 | 0.913725 0.247059 0.247059
804 | ]
805 | }
806 | DEF RED_LED_3 LED {
807 | translation -0.130097 0.0802345 0.0531009
808 | rotation 1 0 0 0
809 | children [
810 | DEF RED_LED_SHAPE Group {
811 | children [
812 | Shape {
813 | appearance PBRAppearance {
814 | baseColor 1 0 0
815 | metalness 0
816 | roughness 0.3
817 | transparency 0.395718
818 | }
819 | geometry USE LED_SHAPE
820 | }
821 | ]
822 | }
823 | ]
824 | name "red led 3"
825 | color [
826 | 0.913725 0.247059 0.247059
827 | ]
828 | }
829 | DEF RIGHT_WHEEL HingeJoint {
830 | device [
831 | RotationalMotor {
832 | name "right wheel"
833 | maxVelocity 12.3
834 | }
835 | PositionSensor {
836 | name "right wheel sensor"
837 | }
838 | ]
839 | jointParameters HingeJointParameters {
840 | axis -1 0 0
841 | anchor 0.165032 -0.0001156 0
842 | }
843 | endPoint Solid {
844 | translation 0.165032 -0.0001156 0
845 | rotation -1 0 0 0
846 | children [
847 | DEF RIGHT_BLACK_CYLINDER_SHAPE Shape {
848 | appearance PBRAppearance {
849 | baseColor 0 0.0051864 0
850 | metalness 0
851 | roughness 0.3
852 | }
853 | geometry IndexedFaceSet {
854 | coord DEF coord_RIGHT_BLACK_CYLINDER Coordinate {
855 | point [
856 | 0.024245 0.0067816 -0.0017403, 0.024245 0.0067431 0.0018836 0.024245 0.0048978 0.0050029, 0.024245 0.0017403 0.0067816 0.024245 -0.0018837 0.0067431, 0.024245 -0.0050029 0.0048979 0.024245 -0.0067816 0.0017402, 0.024245 -0.0067431 -0.0018837 0.024245 -0.0048978 -0.0050029, 0.024245 -0.0017403 -0.0067816 0.024245 0.0018837 -0.0067431, 0.024245 0.0050029 -0.0048979 0.0220984 0.0067816 -0.0017403, 0.0220984 0.0067434 0.0018838 0.0220984 0.004898 0.0050029, 0.0220984 0.0017402 0.0067815 0.0220984 -0.0018837 0.0067431, 0.0220984 -0.0050029 0.0048979 0.0220984 -0.0067815 0.0017403, 0.0220984 -0.0067431 -0.0018837 0.0220984 -0.0048978 -0.0050029, 0.0220984 -0.0017403 -0.0067816 0.0220984 0.0018837 -0.0067431, 0.0220984 0.0050029 -0.0048979 0.024245 0 0
857 | ]
858 | }
859 | coordIndex [
860 | 24 0 1 -1 24 1 2 -1 24 2 3 -1 24 3 4 -1 24 4 5 -1 24 5 6 -1 24 6 7 -1 24 7 8 -1 24 8 9 -1 24 9 10 -1 24 10 11 -1 11 0 24 -1 12 0 11 -1 12 11 23 -1 10 22 23 -1 10 23 11 -1 9 21 22 -1 9 22 10 -1 8 20 21 -1 8 21 9 -1 7 19 20 -1 7 20 8 -1 6 18 19 -1 6 19 7 -1 5 17 18 -1 5 18 6 -1 4 16 17 -1 4 17 5 -1 3 15 16 -1 3 16 4 -1 2 14 15 -1 2 15 3 -1 1 13 14 -1 1 14 2 -1 0 12 1 -1 12 13 1 -1
861 | ]
862 | creaseAngle 1
863 | }
864 | }
865 | DEF RIGHT_BOLT_SHAPE Shape {
866 | appearance PBRAppearance {
867 | baseColor 0.689949 0.689949 0.689949
868 | roughness 0.3
869 | }
870 | geometry IndexedFaceSet {
871 | coord DEF coord_rightBolt Coordinate {
872 | point [
873 | 0.0230439 3.56e-05 -0.003356, 0.0230439 -0.0028885 -0.0017088 0.0230439 -0.0029241 0.0016472, 0.0230439 -3.56e-05 0.003356 0.0230439 0.0028886 0.0017088, 0.0230439 0.0029242 -0.0016472 0.0249875 3.56e-05 -0.003356, 0.0249875 -0.0028885 -0.0017088 0.0249875 -0.0029241 0.0016472, 0.0249875 -3.56e-05 0.003356 0.0249875 0.0028886 0.0017088, 0.0249875 0.0029242 -0.0016472 0.0249875 0 0
874 | ]
875 | }
876 | coordIndex [
877 | 12 7 6 -1 12 8 7 -1 12 9 8 -1 12 10 9 -1 12 11 10 -1 12 6 11 -1 6 0 5 -1 6 5 11 -1 4 10 11 -1 4 11 5 -1 3 9 10 -1 3 10 4 -1 2 8 9 -1 2 9 3 -1 1 7 8 -1 1 8 2 -1 0 6 7 -1 0 7 1 -1
878 | ]
879 | creaseAngle 1
880 | }
881 | }
882 | USE RIM_SHAPE
883 | USE TIRE_SHAPE
884 | ]
885 | name "right wheel"
886 | boundingObject USE BOUNDING_WHEEL
887 | physics Physics {
888 | }
889 | }
890 | }
891 | DEF SO_0 Pioneer3DistanceSensor {
892 | translation -0.140208 0.114 -0.0610447
893 | rotation 0 1 0 3.14159
894 | name "so0"
895 | }
896 | DEF SO_1 Pioneer3DistanceSensor {
897 | translation -0.122255 0.114 -0.110288
898 | rotation 0 1 0 2.44346
899 | name "so1"
900 | }
901 | DEF SO_10 Pioneer3DistanceSensor {
902 | translation 0.07738 0.114 0.239181
903 | rotation 0 -1 0 1.0472
904 | name "so10"
905 | }
906 | DEF SO_11 Pioneer3DistanceSensor {
907 | translation 0.0258761 0.114 0.257812
908 | rotation 0 -1 0 1.39626
909 | name "so11"
910 | }
911 | DEF SO_12 Pioneer3DistanceSensor {
912 | translation -0.0289131 0.114 0.257812
913 | rotation 0 -1 0 1.74533
914 | name "so12"
915 | }
916 | DEF SO_13 Pioneer3DistanceSensor {
917 | translation -0.0803968 0.114 0.239181
918 | rotation 0 -1 0 2.0944
919 | name "so13"
920 | }
921 | DEF SO_14 Pioneer3DistanceSensor {
922 | translation -0.122403 0.114 0.204065
923 | rotation 0 -1 0 2.44346
924 | name "so14"
925 | }
926 | DEF SO_15 Pioneer3DistanceSensor {
927 | translation -0.140311 0.114 0.154945
928 | rotation 0 -1 0 3.14159
929 | name "so15"
930 | }
931 | DEF SO_2 Pioneer3DistanceSensor {
932 | translation -0.0801434 0.114 -0.145492
933 | rotation 0 1 0 2.0944
934 | name "so2"
935 | }
936 | DEF SO_3 Pioneer3DistanceSensor {
937 | translation -0.0285304 0.114 -0.16417
938 | rotation 0 1 0 1.74533
939 | name "so3"
940 | }
941 | DEF SO_4 Pioneer3DistanceSensor {
942 | translation 0.026383 0.114 -0.16417
943 | rotation 0 1 0 1.39626
944 | name "so4"
945 | }
946 | DEF SO_5 Pioneer3DistanceSensor {
947 | translation 0.0780296 0.114 -0.145492
948 | rotation 0 1 0 1.0472
949 | name "so5"
950 | }
951 | DEF SO_6 Pioneer3DistanceSensor {
952 | translation 0.120142 0.114 -0.110288
953 | rotation 0 1 0 0.698132
954 | name "so6"
955 | }
956 | DEF SO_7 Pioneer3DistanceSensor {
957 | translation 0.138094 0.114 -0.0610446
958 | name "so7"
959 | }
960 | DEF SO_8 Pioneer3DistanceSensor {
961 | translation 0.137294 0.114 0.154945
962 | name "so8"
963 | }
964 | DEF SO_9 Pioneer3DistanceSensor {
965 | translation 0.119387 0.114 0.204065
966 | rotation 0 -1 0 0.698132
967 | name "so9"
968 | }
969 | DEF UPPER_YELLOW_LED LED {
970 | translation -0.130135 0.105728 0.0530564
971 | rotation 1 0 0 0
972 | children [
973 | USE YELLOW_LED_SHAPE
974 | ]
975 | name "yellow led"
976 | color [
977 | 0.929412 0.933333 0.615686
978 | ]
979 | }
980 | DEF WHITE_LED LED {
981 | translation -0.130106 0.0802345 0.072656
982 | rotation 1 0 0 0
983 | children [
984 | DEF WHITE_LED_SHAPE Shape {
985 | appearance PBRAppearance {
986 | metalness 0
987 | roughness 0.3
988 | transparency 0.395718
989 | }
990 | geometry USE LED_SHAPE
991 | }
992 | ]
993 | name "white led"
994 | color [
995 | 1 1 1
996 | ]
997 | }
998 | Group {
999 | children IS extensionSlot
1000 | }
1001 | ]
1002 | name IS name
1003 | model "Adept Pioneer 3-DX"
1004 | boundingObject Group {
1005 | children [
1006 | DEF TOP_FRONT_CYLINDER Transform {
1007 | translation 0 0.142 0.021
1008 | children [
1009 | Cylinder {
1010 | height 0.007
1011 | radius 0.2
1012 | subdivision 24
1013 | }
1014 | ]
1015 | }
1016 | DEF TOP_BACK_CYLINDER Transform {
1017 | translation 0 0.142 0.087
1018 | children [
1019 | Cylinder {
1020 | height 0.007
1021 | radius 0.18
1022 | subdivision 24
1023 | }
1024 | ]
1025 | }
1026 | DEF FRONT_RING Transform {
1027 | translation 0 0.112 0.114
1028 | children [
1029 | Cylinder {
1030 | height 0.05
1031 | radius 0.15
1032 | subdivision 24
1033 | }
1034 | ]
1035 | }
1036 | DEF BACK_RING Transform {
1037 | translation 0 0.112 -0.023
1038 | children [
1039 | Cylinder {
1040 | height 0.05
1041 | radius 0.15
1042 | subdivision 24
1043 | }
1044 | ]
1045 | }
1046 | DEF LARGE_BOX Transform {
1047 | translation 0 0.0285 0.04
1048 | children [
1049 | Box {
1050 | size 0.2 0.115 0.341
1051 | }
1052 | ]
1053 | }
1054 | DEF BAR_BOX Transform {
1055 | translation 0 0.0415 0.234
1056 | children [
1057 | Box {
1058 | size 0.1356 0.007 0.039
1059 | }
1060 | ]
1061 | }
1062 | DEF SIDES Transform {
1063 | translation 0 0.0285 0.0427
1064 | children [
1065 | Box {
1066 | size 0.261 0.115 0.274
1067 | }
1068 | ]
1069 | }
1070 | DEF BACK_LEFT_CORNER Transform {
1071 | translation -0.1029 0.0285 0.1825
1072 | rotation 0 1 0 0.79
1073 | children [
1074 | Box {
1075 | size 0.037 0.115 0.044
1076 | }
1077 | ]
1078 | }
1079 | DEF BACK_RIGHT_CORNER Transform {
1080 | translation 0.1029 0.0285 0.1825
1081 | rotation 0 1 0 -0.79
1082 | children [
1083 | Box {
1084 | size 0.037 0.115 0.044
1085 | }
1086 | ]
1087 | }
1088 | DEF FRONT_LEFT_CORNER Transform {
1089 | translation -0.1019 0.0285 -0.1005
1090 | rotation 0 1 0 -0.7
1091 | children [
1092 | Box {
1093 | size 0.037 0.115 0.047
1094 | }
1095 | ]
1096 | }
1097 | DEF FRONT_RIGHT_CORNER Transform {
1098 | translation 0.1019 0.0285 -0.1005
1099 | rotation 0 1 0 0.7
1100 | children [
1101 | Box {
1102 | size 0.037 0.115 0.047
1103 | }
1104 | ]
1105 | }
1106 | ]
1107 | }
1108 | physics Physics {
1109 | density -1
1110 | mass 6.73
1111 | centerOfMass [
1112 | 0 0.06 0.06
1113 | ]
1114 | }
1115 | controller IS controller
1116 | controllerArgs IS controllerArgs
1117 | customData IS customData
1118 | supervisor IS supervisor
1119 | synchronization IS synchronization
1120 | }
1121 | }
1122 |
--------------------------------------------------------------------------------
/protos/RectangleArena.proto:
--------------------------------------------------------------------------------
1 | #VRML_SIM R2019b utf8
2 | # license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
3 | # license url: https://cyberbotics.com/webots_assets_license
4 | # tags: static
5 | # A configurable rectangle arena composed of a floor surrounded by walls.
6 |
7 | PROTO RectangleArena [
8 | field SFVec3f translation 0 0 0
9 | field SFRotation rotation 0 1 0 0
10 | field SFString name "rectangle arena"
11 | field SFString contactMaterial "default" # Is `Solid.contactMaterial`.
12 | field SFVec2f floorSize 1 1 # Defines the size of the floor.
13 | field SFVec2f floorTileSize 0.5 0.5 # Defines the size of the texture used for the floor.
14 | field SFNode floorAppearance ChequeredParquetry {} # Defines the appearance of the floor.
15 | field SFFloat wallThickness 0.01 # Defines the thickness of the walls.
16 | field SFFloat wallHeight 0.1 # Defines the height of the walls.
17 | field SFNode wallAppearance BrushedAluminium {} # Defines the appearance of the wall.
18 |
19 | # Deprecated in R2019a
20 | hiddenField MFString floorTextureUrl "textures/checkered_parquetry.jpg"
21 | hiddenField MFString wallTextureUrl "textures/metal.jpg"
22 | # Deprecated in R2019a-rev2
23 | hiddenField SFColor wallColor 0.8 0.8 0.8
24 | hiddenField SFVec2f wallTileSize 0.5 0.5
25 | ]
26 | {
27 | %{
28 |
29 | local wbcore = require("wbcore")
30 | local floorSize = fields.floorSize.value
31 | if floorSize.x <= 0.0 or floorSize.y <= 0.0 then
32 | io.stderr:write("'floorSize' must contain positive values\n")
33 | floorSize = fields.floorSize.defaultValue
34 | end
35 |
36 | if fields.floorTextureUrl.value[0] ~= fields.floorTextureUrl.defaultValue[0] then
37 | io.stderr:write("The 'floorTextureUrl' field is deprecated, using the new 'floorAppearance' field instead.\n")
38 | end
39 |
40 | if fields.wallTextureUrl.value[0] ~= fields.wallTextureUrl.defaultValue[0] then
41 | io.stderr:write("The 'wallTextureUrl' field is deprecated, using the new 'wallAppearance' field instead.\n")
42 | end
43 |
44 | if (fields.wallColor.value.r ~= fields.wallColor.defaultValue.r or
45 | fields.wallColor.value.g ~= fields.wallColor.defaultValue.g or
46 | fields.wallColor.value.b ~= fields.wallColor.defaultValue.b) then
47 | io.stderr:write("The 'wallColor' field is deprecated, using the new 'wallAppearance' field instead.\n")
48 | end
49 |
50 | local wallTileSize = fields.wallTileSize.value;
51 | if (wallTileSize.x ~= fields.wallTileSize.defaultValue.x or wallTileSize.y ~= fields.wallTileSize.defaultValue.y) then
52 | io.stderr:write("The 'wallTileSize' field is deprecated, using the new 'wallApperance' field instead.\n")
53 | end
54 |
55 | local wallThickness = fields.wallThickness.value
56 | if wallThickness <= 0 then
57 | io.stderr:write("'wallThickness' must be positive\n")
58 | wallThickness = fields.wallThickness.defaultValue
59 | end
60 |
61 | local wallHeight = fields.wallHeight.value
62 | if wallHeight <= 0 then
63 | io.stderr:write("'wallHeight' must be positive\n")
64 | wallHeight = fields.wallHeight.defaultValue
65 | end
66 | }%
67 | Solid {
68 | translation IS translation
69 | rotation IS rotation
70 | children [
71 | Floor {
72 | size %{= floorSize.x }% %{= floorSize.y }%
73 | tileSize IS floorTileSize
74 | appearance IS floorAppearance
75 | contactMaterial IS contactMaterial
76 | }
77 | SolidBox {
78 | translation %{= floorSize.x / 2 + wallThickness / 2 }% %{= wallHeight / 2 }% 0
79 | name "wall"
80 | size %{= wallThickness }% %{= wallHeight }% %{= floorSize.y }%
81 | appearance IS wallAppearance
82 | contactMaterial IS contactMaterial
83 | }
84 | SolidBox {
85 | translation %{= -(floorSize.x / 2 + wallThickness / 2) }% %{= wallHeight / 2 }% 0
86 | name "wall#2"
87 | size %{= wallThickness }% %{= wallHeight }% %{= floorSize.y }%
88 | appearance IS wallAppearance
89 | contactMaterial IS contactMaterial
90 | }
91 | SolidBox {
92 | translation 0 %{= wallHeight / 2 }% %{= floorSize.y / 2 + wallThickness / 2 }%
93 | name "wall#3"
94 | size %{= floorSize.x + 2 * wallThickness }% %{= wallHeight }% %{= wallThickness }%
95 | appearance IS wallAppearance
96 | contactMaterial IS contactMaterial
97 | }
98 | SolidBox {
99 | translation 0 %{= wallHeight / 2 }% %{= -(floorSize.y / 2 + wallThickness / 2) }%
100 | name "wall#4"
101 | size %{= floorSize.x + 2 * wallThickness }% %{= wallHeight }% %{= wallThickness }%
102 | appearance IS wallAppearance
103 | contactMaterial IS contactMaterial
104 | }
105 | ]
106 | name IS name
107 | model "rectangle arena"
108 | }
109 | }
110 |
--------------------------------------------------------------------------------
/protos/SandyGround.proto:
--------------------------------------------------------------------------------
1 | #VRML_SIM R2019b utf8
2 | # license: Apache License 2.0
3 | # license url: http://www.apache.org/licenses/LICENSE-2.0
4 | # A sandy ground material. The color can be selected using the `colorOverride` field. Useful with the UnevenTerrain PROTO.
5 |
6 | PROTO SandyGround [
7 | field SFColor colorOverride 1 1 1 # Defines the default color multiplied with the texture color.
8 | field SFNode textureTransform TextureTransform { scale 4 4 } # Defines an optional 2d texture transform.
9 | field SFFloat IBLStrength 1 # Defines the strength of ambient lighting from the Cubemap node.
10 | ]
11 | {
12 | PBRAppearance {
13 | baseColor IS colorOverride
14 | baseColorMap ImageTexture {
15 | url [
16 | "textures/rover_circuit.jpg"
17 | ]
18 | filtering 5
19 | }
20 | roughnessMap ImageTexture {
21 | url [
22 | "textures/rover_circuit.jpg"
23 | ]
24 | filtering 5
25 | }
26 | normalMap ImageTexture {
27 | url [
28 | "textures/rover_circuit.jpg"
29 | ]
30 | filtering 5
31 | }
32 | occlusionMap ImageTexture {
33 | url [
34 | "textures/rover_circuit.jpg"
35 | ]
36 | filtering 5
37 | }
38 | metalness 0
39 | normalMapFactor 1
40 | IBLStrength IS IBLStrength
41 | textureTransform IS textureTransform
42 | }
43 | }
44 |
--------------------------------------------------------------------------------
/protos/UnevenTerrain.proto:
--------------------------------------------------------------------------------
1 | #VRML_SIM R2019b utf8
2 | # license: Copyright Cyberbotics Ltd. Licensed for use only with Webots.
3 | # license url: https://cyberbotics.com/webots_assets_license
4 | # Randomly generated uneven terrain based on Perlin noise.
5 |
6 | PROTO UnevenTerrain [
7 | field SFVec3f translation 0 0 0
8 | field SFRotation rotation 0 1 0 0
9 | field SFString name "uneven terrain"
10 | field SFVec3f size 50 5 50 # Defines the size of the terrain.
11 | field SFInt32 xDimension 50 # Defines the number of points in the grid height array in the x direction.
12 | field SFInt32 zDimension 50 # Defines the number of points in the grid height array in the y direction.
13 | field SFNode appearance SandyGround {} # Defines the appearance of the terrain.
14 | field SFVec2f textureScale 1.0 1.0 # Defines the size of the textures used for the terrain.
15 | field SFInt32 randomSeed 1 # Defines the seed of the random number generator. A value smaller or equal to 0 sets a random seed.
16 | field SFBool flatCenter FALSE # Defines whether the center of the terrain should be flat.
17 | field SFBool flatBounds FALSE # Defines whether the bounds of the terrain should be flat.
18 | field SFInt32 perlinNOctaves 3 # Defines the number of octaves of the perlin noise.
19 |
20 | # Deprecated in Webots R2019a
21 | hiddenField MFString texture "textures/sand.jpg"
22 | ]
23 | {
24 | %{
25 | -- Reference: https://stackoverflow.com/a/42543313/2210777
26 |
27 | local wbcore = require('wbcore')
28 | local wbrandom = require('wbrandom')
29 | local os = require('os')
30 |
31 | if fields.randomSeed.value <= 0 then
32 | wbrandom.seed(os.clock() + os.time())
33 | else
34 | wbrandom.seed(fields.randomSeed.value)
35 | end
36 |
37 | function gaussian2d(x, y, amp, cx, cy, sx, sy)
38 | return amp * math.exp( - ( ( math.pow(x - cx, 2) / (2.0 * math.pow(sx, 2)) ) + (math.pow(y - cy, 2) / (2.0 * math.pow(sy, 2)) ) ))
39 | end
40 |
41 | -- Create 256 shuffled numbers repeated twice.
42 | local perm = {}
43 | for i = 1, 256 do
44 | table.insert(perm, wbrandom.integer(i), i)
45 | end
46 | for i = 1, 256 do
47 | perm[i + 256] = perm[i]
48 | end
49 |
50 | -- Generate 256 directions
51 | local dirs = {}
52 | for a = 0, 255 do
53 | table.insert(dirs, {
54 | math.cos(a * 2.0 * math.pi / 256),
55 | math.sin(a * 2.0 * math.pi / 256)
56 | })
57 | end
58 |
59 | local function noise(x, y, per)
60 | local function surflet(grid_x, grid_y)
61 | local dist_x, dist_y = math.abs(x - grid_x), math.abs(y - grid_y)
62 | local poly_x = 1 - 6 * dist_x ^ 5 + 15 * dist_x ^ 4 - 10 * dist_x ^ 3
63 | local poly_y = 1 - 6 * dist_y ^ 5 + 15 * dist_y ^ 4 - 10 * dist_y ^ 3
64 | local hashed = perm[(perm[(math.floor(grid_x) % per) + 1] + math.floor(grid_y) % per) + 1]
65 | local grad = (x - grid_x) * dirs[hashed][1] + (y - grid_y) * dirs[hashed][2]
66 | return poly_x * poly_y * grad
67 | end
68 | local int_x, int_y = math.floor(x), math.floor(y)
69 | return surflet(int_x + 0, int_y + 0) + surflet(int_x + 1, int_y + 0) +
70 | surflet(int_x + 0, int_y + 1) + surflet(int_x + 1, int_y + 1)
71 | end
72 |
73 | local function fBm(x, y, per, octs) -- Fractional Brownian motion
74 | local val = 0
75 | for o = 0, octs - 1 do
76 | val = val + (0.5 ^ o * noise(x * 2 ^ o, y * 2 ^ o, per * 2 ^ o))
77 | end
78 | return val
79 | end
80 |
81 | local perlinSize = 128
82 | local nOctave = fields.perlinNOctaves.value
83 |
84 | local size = fields.size.value
85 | local xDimension = fields.xDimension.value
86 | local zDimension = fields.zDimension.value
87 |
88 | local textureScale = { x = size.x / fields.textureScale.value.x, y = size.z / fields.textureScale.value.y }
89 | }%
90 | Solid {
91 | translation IS translation
92 | rotation IS rotation
93 | children [
94 | Shape {
95 | appearance IS appearance
96 | geometry IndexedFaceSet {
97 | coord Coordinate {
98 | point [
99 | %{ for j = 0, zDimension do }%
100 | %{ y = -(size.z / 2) + j * (size.z / zDimension) }%
101 | %{ for i = 0, xDimension do }%
102 | %{
103 | local height = 1.0
104 | local x = i / xDimension
105 | local z = j / zDimension
106 | if nOctave > 0 then
107 | height = 0.5 * (1.0 + fBm(z, x, perlinSize, nOctave))
108 | end
109 | if fields.flatCenter.value then
110 | height = height * (1.0 - gaussian2d(x - 0.5, z - 0.5, 1, 0, 0, 0.2, 0.2))
111 | end
112 | if fields.flatBounds.value then
113 | height = height * gaussian2d(x - 0.5, z - 0.5, 1, 0, 0, 0.2, 0.2)
114 | end
115 | height = height * size.y
116 | }%
117 | %{= -(size.x / 2) + i * (size.x / xDimension) }% %{= height}% %{= y }%
118 | %{ end }%
119 | %{ end }%
120 | ]
121 | }
122 | texCoord TextureCoordinate {
123 | point [
124 | %{ for j = 0, zDimension do }%
125 | %{ y = (1.0 - j * (1.0 / zDimension) )}%
126 | %{ for i = 0, xDimension do }%
127 | %{= i * (1.0 / xDimension) * textureScale.x }% %{= y * textureScale.y }%
128 | %{ end }%
129 | %{ end }%
130 | ]
131 | }
132 | coordIndex [
133 | %{ local width = xDimension + 1 }%
134 | %{ for j = 0, zDimension - 1 do }%
135 | %{ for i = 0, xDimension - 1 do }%
136 | %{= i + j * width }% %{= i + (j + 1) * width }% %{= (i + 1) + (j + 1) * width }% %{= (i + 1) + j * width }% -1
137 | %{ end }%
138 | %{ end }%
139 | ]
140 | creaseAngle 1
141 | }
142 | }
143 | ]
144 | name IS name
145 | model "uneven terrain"
146 | boundingObject DEF UNEVEN_TERRAIN_ELEVATION_GRID Transform {
147 | translation %{= - size.x / 2 }% 0 %{= - size.z / 2 }%
148 | children [
149 | ElevationGrid {
150 | %{ if xDimension > 2 and zDimension > 2 then }%
151 | xDimension IS xDimension
152 | xSpacing %{= size.x / xDimension }%
153 | zDimension IS zDimension
154 | zSpacing %{= size.z / zDimension }%
155 |
156 | height [
157 | %{ for i=0, xDimension - 1 do }%
158 | %{ for j=0, zDimension - 1 do }%
159 | %{
160 | local height = 1.0
161 | local x = i / xDimension
162 | local z = j / zDimension
163 | if nOctave > 0 then
164 | height = 0.5 * (1.0 + fBm(x, z, perlinSize, nOctave))
165 | end
166 | if fields.flatCenter.value then
167 | height = height * (1.0 - gaussian2d(x - 0.5, z - 0.5, 1, 0, 0, 0.2, 0.2))
168 | end
169 | if fields.flatBounds.value then
170 | height = height * gaussian2d(x - 0.5, z - 0.5, 1, 0, 0, 0.2, 0.2)
171 | end
172 | height = height * size.y
173 | }%
174 | %{= height }%
175 | %{ end }%
176 | %{ end }%
177 | ]
178 | %{ end }%
179 | }
180 | ]
181 | }
182 | }
183 | }
184 |
--------------------------------------------------------------------------------
/protos/icons/CircleArena.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/icons/CircleArena.png
--------------------------------------------------------------------------------
/protos/icons/Floor.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/icons/Floor.png
--------------------------------------------------------------------------------
/protos/icons/Pioneer3DistanceSensor.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/icons/Pioneer3DistanceSensor.png
--------------------------------------------------------------------------------
/protos/icons/Pioneer3Gripper.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/icons/Pioneer3Gripper.png
--------------------------------------------------------------------------------
/protos/icons/Pioneer3at.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/icons/Pioneer3at.png
--------------------------------------------------------------------------------
/protos/icons/Pioneer3dx.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/icons/Pioneer3dx.png
--------------------------------------------------------------------------------
/protos/icons/RectangleArena.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/icons/RectangleArena.png
--------------------------------------------------------------------------------
/protos/icons/UnevenTerrain.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/icons/UnevenTerrain.png
--------------------------------------------------------------------------------
/protos/textures/Aruco.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/Aruco.png
--------------------------------------------------------------------------------
/protos/textures/body_3at_base_color.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/body_3at_base_color.jpg
--------------------------------------------------------------------------------
/protos/textures/body_3at_normal.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/body_3at_normal.jpg
--------------------------------------------------------------------------------
/protos/textures/body_3at_occlusion.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/body_3at_occlusion.jpg
--------------------------------------------------------------------------------
/protos/textures/body_3at_roughness.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/body_3at_roughness.jpg
--------------------------------------------------------------------------------
/protos/textures/body_3dx_base_color.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/body_3dx_base_color.jpg
--------------------------------------------------------------------------------
/protos/textures/body_3dx_metalness.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/body_3dx_metalness.jpg
--------------------------------------------------------------------------------
/protos/textures/body_3dx_normal.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/body_3dx_normal.jpg
--------------------------------------------------------------------------------
/protos/textures/body_3dx_occlusion.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/body_3dx_occlusion.jpg
--------------------------------------------------------------------------------
/protos/textures/body_3dx_roughness.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/body_3dx_roughness.jpg
--------------------------------------------------------------------------------
/protos/textures/caster_wheel.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/caster_wheel.jpg
--------------------------------------------------------------------------------
/protos/textures/caster_wheel_base_color.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/caster_wheel_base_color.jpg
--------------------------------------------------------------------------------
/protos/textures/caster_wheel_normal.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/caster_wheel_normal.jpg
--------------------------------------------------------------------------------
/protos/textures/caster_wheel_occlusion.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/caster_wheel_occlusion.jpg
--------------------------------------------------------------------------------
/protos/textures/caster_wheel_roughness.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/caster_wheel_roughness.jpg
--------------------------------------------------------------------------------
/protos/textures/cross_tire.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/cross_tire.jpg
--------------------------------------------------------------------------------
/protos/textures/cross_tire_base_color.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/cross_tire_base_color.jpg
--------------------------------------------------------------------------------
/protos/textures/cross_tire_normal.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/cross_tire_normal.jpg
--------------------------------------------------------------------------------
/protos/textures/cross_tire_occlusion.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/cross_tire_occlusion.jpg
--------------------------------------------------------------------------------
/protos/textures/honeycomb_base_color.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/honeycomb_base_color.jpg
--------------------------------------------------------------------------------
/protos/textures/honeycomb_normal.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/honeycomb_normal.jpg
--------------------------------------------------------------------------------
/protos/textures/rover_circuit.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/rover_circuit.jpg
--------------------------------------------------------------------------------
/protos/textures/serial_plug.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/serial_plug.jpg
--------------------------------------------------------------------------------
/protos/textures/smooth_rubber.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/smooth_rubber.jpg
--------------------------------------------------------------------------------
/protos/textures/smooth_rubber_base_color.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/smooth_rubber_base_color.jpg
--------------------------------------------------------------------------------
/protos/textures/smooth_rubber_normal.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/smooth_rubber_normal.jpg
--------------------------------------------------------------------------------
/protos/textures/smooth_rubber_occlusion.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/smooth_rubber_occlusion.jpg
--------------------------------------------------------------------------------
/protos/textures/smooth_rubber_roughness.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/smooth_rubber_roughness.jpg
--------------------------------------------------------------------------------
/protos/textures/top_3at_base_color.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/top_3at_base_color.jpg
--------------------------------------------------------------------------------
/protos/textures/top_3at_base_color_copy.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/top_3at_base_color_copy.jpg
--------------------------------------------------------------------------------
/protos/textures/top_3dx_base_color.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/top_3dx_base_color.jpg
--------------------------------------------------------------------------------
/protos/textures/top_3dx_normal.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/PrasadNR/Webots-Quadcopter-Python-SITL/f36b17dfd95006192d66a453d9fcdafb47662dc3/protos/textures/top_3dx_normal.jpg
--------------------------------------------------------------------------------
/worlds/.ObjectTracking.wbproj:
--------------------------------------------------------------------------------
1 | Webots Project File version R2019b
2 | perspectives: 000000ff00000000fd00000003000000000000000000000000fc0100000001fb0000001a0044006f00630075006d0065006e0074006100740069006f006e0000000000ffffffff0000006900ffffff000000010000011c0000033cfc0200000001fb0000001400540065007800740045006400690074006f0072010000001a0000033c0000004100ffffff00000003000007800000007afc0100000001fb0000000e0043006f006e0073006f006c00650100000000000007800000006900ffffff000006620000033c00000001000000020000000100000008fc00000000
3 | simulationViewPerspectives: 000000ff000000010000000200000118000005480100000002010000000100
4 | sceneTreePerspectives: 000000ff000000010000000200000267000000fa0100000002010000000200
5 | maximizedDockId: -1
6 | centralWidgetVisible: 1
7 | selectionDisabled: 0
8 | viewpointLocked: 0
9 | orthographicViewHeight: 1
10 | textFiles: -1
11 | renderingDevicePerspectives: Mavic 2 PRO:camera;1;1;0;0
12 |
--------------------------------------------------------------------------------
/worlds/.empty.wbproj:
--------------------------------------------------------------------------------
1 | Webots Project File version R2019b
2 | perspectives: 000000ff00000000fd000000030000000000000320000003ecfc0100000003fc00000000ffffffff0000000000fffffffc0200000001fb00000012005300630065006e0065005400720065006501000000000000039f0000000000000000fb0000001e00480074006d006c0052006f0062006f007400570069006e0064006f00770000000000000003200000000000000000fb0000001a0044006f00630075006d0065006e0074006100740069006f006e0000000000ffffffff0000006900ffffff00000001000001db000002dcfc0200000001fb0000001400540065007800740045006400690074006f0072000000001a000002dc0000004100ffffff0000000300000780000000dafc0100000001fb0000000e0043006f006e0073006f006c00650100000000000007800000006900ffffff00000780000002dc00000004000000040000000100000008fc00000000
3 | simulationViewPerspectives: 000000ff00000001000000020000016c000004a00100000002010000000101
4 | sceneTreePerspectives: 000000ff0000000100000002000000c0000001120100000002010000000201
5 | minimizedPerspectives: 000000ff00000000fd000000030000000000000320000003ecfc0100000003fc00000000ffffffff0000000000fffffffc0200000001fb00000012005300630065006e0065005400720065006501000000000000039f0000000000000000fb0000001e00480074006d006c0052006f0062006f007400570069006e0064006f00770000000000000003200000000000000000fb0000001a0044006f00630075006d0065006e0074006100740069006f006e0000000000ffffffff0000006900ffffff00000001000001db00000310fc0200000001fb0000001400540065007800740045006400690074006f0072010000001a000003100000008700ffffff0000000300000781000000dafc0100000001fb0000000e0043006f006e0073006f006c00650100000000000007810000006900ffffff000005a40000031000000004000000040000000100000008fc00000000
6 | maximizedDockId: -1
7 | centralWidgetVisible: 1
8 | selectionDisabled: 0
9 | viewpointLocked: 0
10 | orthographicViewHeight: 1
11 | textFiles: -1
12 | renderingDevicePerspectives: Mavic 2 PRO:camera;1;1;0;0
13 | renderingDevicePerspectives: Pioneer 3-AT:camera;0;1.01563;0;0
14 | renderingDevicePerspectives: Pioneer 3-AT:display;1;1;0;0
15 |
--------------------------------------------------------------------------------
/worlds/ObjectTracking.wbt:
--------------------------------------------------------------------------------
1 | #VRML_SIM R2019b utf8
2 | WorldInfo {
3 | }
4 | Viewpoint {
5 | orientation -0.9998968088218009 0.003034175486868184 0.01404156284370101 1.2555537990264856
6 | position -7.949513111269061 27.57058278040368 3.586840463428051
7 | }
8 | TexturedBackground {
9 | }
10 | TexturedBackgroundLight {
11 | }
12 | Pioneer3at {
13 | translation -5.1444484422575286e-05 0.107611069497796 -3.2998556360533344
14 | rotation -0.00019720603968113445 0.999999905409869 0.00038767258171790284 2.2000000413131686
15 | controller "pioneerController"
16 | extensionSlot [
17 | Compass {
18 | }
19 | Emitter {
20 | }
21 | GPS {
22 | }
23 | ]
24 | }
25 | Floor {
26 | size 70 42.4
27 | tileSize 70 42.4
28 | appearance SandyGround {
29 | textureTransform TextureTransform {
30 | }
31 | }
32 | }
33 | Mavic2Pro {
34 | translation 0 0.35 -3.3
35 | rotation 1 0 0 -1.570796327
36 | controller "mavic2proController"
37 | bodySlot [
38 | Receiver {
39 | }
40 | ]
41 | cameraSlot [
42 | Camera {
43 | rotation 1 0 0 -1
44 | width 400
45 | height 240
46 | }
47 | ]
48 | }
49 |
--------------------------------------------------------------------------------