diff --git a/aruco_pose/src/genmap.py b/aruco_pose/src/genmap.py
index 0050fc4f8..81fc76b9f 100755
--- a/aruco_pose/src/genmap.py
+++ b/aruco_pose/src/genmap.py
@@ -1,4 +1,4 @@
-#!/usr/bin/env python
+#!/usr/bin/env python3
# Copyright (C) 2018 Copter Express Technologies
#
diff --git a/aruco_pose/test/largemap.py b/aruco_pose/test/largemap.py
index 56e06837b..60e9c5e27 100755
--- a/aruco_pose/test/largemap.py
+++ b/aruco_pose/test/largemap.py
@@ -1,26 +1,19 @@
-#!/usr/bin/env python
-import sys
-import unittest
-import json
import rospy
-import rostest
+import pytest
from sensor_msgs.msg import Image
from visualization_msgs.msg import MarkerArray as VisMarkerArray
+@pytest.fixture
+def node():
+ return rospy.init_node('test_aruco_largemap', anonymous=True)
-class TestArucoPose(unittest.TestCase):
- def setUp(self):
- rospy.init_node('test_aruco_largemap', anonymous=True)
+def test_large_map_image(node):
+ img = rospy.wait_for_message('aruco_map/image', Image, timeout=5)
+ assert img.width == 2000
+ assert img.height == 2000
+ assert img.encoding in ('mono8', 'rgb8')
- def test_map_image(self):
- img = rospy.wait_for_message('aruco_map/image', Image, timeout=5)
- self.assertEqual(img.width, 2000)
- self.assertEqual(img.height, 2000)
- self.assertIn(img.encoding, ('mono8', 'rgb8'))
-
- def test_map_visualization(self):
- vis = rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5)
-
-
-rostest.rosrun('aruco_pose', 'test_aruco_largemap', TestArucoPose, sys.argv)
+def test_large_map_visualization(node):
+ vis = rospy.wait_for_message('aruco_map/visualization', VisMarkerArray, timeout=5)
+ assert len(vis.markers) == 11
diff --git a/aruco_pose/test/largemap.test b/aruco_pose/test/largemap.test
index 799e18396..c26da411b 100644
--- a/aruco_pose/test/largemap.test
+++ b/aruco_pose/test/largemap.test
@@ -9,5 +9,6 @@
-
+
+
diff --git a/builder/assets/clever/setup.py b/builder/assets/clever/setup.py
index 1ed75deed..d2169cdbe 100755
--- a/builder/assets/clever/setup.py
+++ b/builder/assets/clever/setup.py
@@ -1,4 +1,4 @@
-#!/usr/bin/env python
+#!/usr/bin/env python3
from distutils.core import setup
diff --git a/builder/assets/python3.yaml b/builder/assets/python3.yaml
new file mode 100644
index 000000000..3a71eb8ab
--- /dev/null
+++ b/builder/assets/python3.yaml
@@ -0,0 +1,9 @@
+python3-wxgtk:
+ debian:
+ buster: [python3-wxgtk4.0]
+python3-serial:
+ debian:
+ buster: [python3-serial]
+python3-requests:
+ debian:
+ buster: [python3-requests]
diff --git a/builder/image-build.sh b/builder/image-build.sh
index fc6f6a03c..4c0a2d708 100755
--- a/builder/image-build.sh
+++ b/builder/image-build.sh
@@ -115,6 +115,7 @@ ${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} exec ${SCRIPTS_DIR}'/image-network.
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/clover.service' '/lib/systemd/system/'
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/roscore.service' '/lib/systemd/system/'
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/melodic-rosdep-clover.yaml' '/etc/ros/rosdep/'
+${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/python3.yaml' '/etc/ros/rosdep/'
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/ros_python_paths' '/etc/sudoers.d/'
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/pigpiod.service' '/lib/systemd/system/'
${BUILDER_DIR}/image-chroot.sh ${IMAGE_PATH} copy ${SCRIPTS_DIR}'/assets/launch.nanorc' '/usr/share/nano/'
diff --git a/builder/image-ros.sh b/builder/image-ros.sh
index fef4aec39..25e7b88f8 100755
--- a/builder/image-ros.sh
+++ b/builder/image-ros.sh
@@ -68,7 +68,8 @@ my_travis_retry() {
# TODO: 'kinetic-rosdep-clover.yaml' should add only if we use our repo?
echo_stamp "Init rosdep"
my_travis_retry rosdep init
-echo "yaml file:///etc/ros/rosdep/melodic-rosdep-clover.yaml" >> /etc/ros/rosdep/sources.list.d/20-default.list
+echo "yaml file:///etc/ros/rosdep/melodic-rosdep-clover.yaml" > /etc/ros/rosdep/sources.list.d/30-clover.list
+echo "yaml file:///etc/ros/rosdep/python3.yaml" > /etc/ros/rosdep/sources.list.d/40-python3.list
my_travis_retry rosdep update
echo_stamp "Populate rosdep for ROS user"
@@ -87,6 +88,7 @@ resolve_rosdep() {
}
export ROS_IP='127.0.0.1' # needed for running tests
+export ROS_PYTHON_VERSION=3
echo_stamp "Reconfiguring Clover repository for simplier unshallowing"
cd /home/pi/catkin_ws/src/clover
@@ -95,8 +97,8 @@ git config remote.origin.fetch "+refs/heads/*:refs/remotes/origin/*"
echo_stamp "Build and install Clover"
cd /home/pi/catkin_ws
resolve_rosdep $(pwd)
-my_travis_retry pip install wheel
-my_travis_retry pip install -r /home/pi/catkin_ws/src/clover/clover/requirements.txt
+my_travis_retry pip3 install wheel
+my_travis_retry pip3 install -r /home/pi/catkin_ws/src/clover/clover/requirements.txt
source /opt/ros/melodic/setup.bash
catkin_make -j2 -DCMAKE_BUILD_TYPE=Release
@@ -133,7 +135,7 @@ echo_stamp "Install GeographicLib datasets (needed for mavros)" \
# FIXME: Buster comes with tornado==5.1.1 but we need tornado==4.2.1 for rosbridge_suite
# (note that Python 3 will still have a more recent version)
-pip install tornado==4.2.1
+pip3 install tornado==4.2.1
echo_stamp "Running tests"
cd /home/pi/catkin_ws
diff --git a/builder/image-software.sh b/builder/image-software.sh
index a94fbf183..0702946c9 100755
--- a/builder/image-software.sh
+++ b/builder/image-software.sh
@@ -67,7 +67,7 @@ apt-get update \
echo "deb http://packages.ros.org/ros/ubuntu buster main" > /etc/apt/sources.list.d/ros-latest.list
echo "deb http://deb.coex.tech/opencv3 buster main" > /etc/apt/sources.list.d/opencv3.list
-echo "deb http://deb.coex.tech/rpi-ros-melodic buster main" > /etc/apt/sources.list.d/rpi-ros-melodic.list
+echo "deb http://deb.coex.tech/melodic-py3 buster main" > /etc/apt/sources.list.d/rpi-ros-melodic.list
echo "deb http://deb.coex.tech/clover buster main" > /etc/apt/sources.list.d/clover.list
echo_stamp "Update apt cache"
@@ -95,20 +95,21 @@ libjpeg8 \
tcpdump \
ltrace \
libpoco-dev \
-python-rosdep \
-python-rosinstall-generator \
-python-wstool \
-python-rosinstall \
+python3-rosdep \
+python3-rosinstall-generator \
+python3-wstool \
+python3-rosinstall \
build-essential \
libffi-dev \
monkey \
pigpio python-pigpio python3-pigpio \
i2c-tools \
-espeak espeak-data python-espeak \
+espeak espeak-data python3-espeak \
ntpdate \
python-dev \
python3-dev \
-python-systemd \
+python3-venv \
+python3-systemd \
mjpg-streamer \
python3-opencv \
&& echo_stamp "Everything was installed!" "SUCCESS" \
@@ -132,13 +133,14 @@ pip3 --version
echo_stamp "Install and enable Butterfly (web terminal)"
echo_stamp "Workaround for tornado >= 6.0 breaking butterfly"
-my_travis_retry pip3 install tornado==5.1.1
+my_travis_retry pip3 install tornado==4.2.1
my_travis_retry pip3 install butterfly
my_travis_retry pip3 install butterfly[systemd]
systemctl enable butterfly.socket
echo_stamp "Install ws281x library"
-my_travis_retry pip install --prefer-binary rpi_ws281x
+my_travis_retry pip2 install --prefer-binary rpi_ws281x
+my_travis_retry pip3 install --prefer-binary rpi_ws281x
echo_stamp "Setup Monkey"
mv /etc/monkey/sites/default /etc/monkey/sites/default.orig
@@ -154,7 +156,7 @@ rm -rf node-v10.15.0-linux-armv6l/
rm node-v10.15.0-linux-armv6l.tar.gz
echo_stamp "Installing ptvsd"
-my_travis_retry pip install ptvsd
+my_travis_retry pip2 install ptvsd
my_travis_retry pip3 install ptvsd
echo_stamp "Add .vimrc"
diff --git a/builder/image-validate.sh b/builder/image-validate.sh
index a95beecd1..43a801ae0 100755
--- a/builder/image-validate.sh
+++ b/builder/image-validate.sh
@@ -18,13 +18,15 @@ echo "Run image tests"
export ROS_DISTRO='melodic'
export ROS_IP='127.0.0.1'
+export ROS_PYTHON_VERSION=3
source /opt/ros/melodic/setup.bash
source /home/pi/catkin_ws/devel/setup.bash
cd /home/pi/catkin_ws/src/clover/builder/test/
./tests.sh
./tests.py
-./tests_py3.py
+# Disable Python 2 tests for image - we're dropping support, right?
+# ./tests_py2.py
[[ $(./tests_clever.py) == "Warning: clever package is renamed to clover" ]] # test backwards compatibility
echo "Move /etc/ld.so.preload back to its original position"
diff --git a/builder/test/tests.py b/builder/test/tests.py
index f676020ec..a33d2eac0 100755
--- a/builder/test/tests.py
+++ b/builder/test/tests.py
@@ -1,4 +1,4 @@
-#!/usr/bin/env python
+#!/usr/bin/env python3
# validate all required modules installed
@@ -17,6 +17,8 @@
from clover.srv import GetTelemetry, Navigate, NavigateGlobal, SetPosition, SetVelocity, \
SetAttitude, SetRates, SetLEDEffect
+get_telemetry = rospy.ServiceProxy('get_telemetry', GetTelemetry)
+
import tf2_ros
import tf2_geometry_msgs
@@ -27,4 +29,4 @@
import pigpio
from espeak import espeak
-print cv2.getBuildInformation()
+print(cv2.getBuildInformation())
diff --git a/builder/test/tests_clever.py b/builder/test/tests_clever.py
index 8db8b6b04..ffe251cc2 100755
--- a/builder/test/tests_clever.py
+++ b/builder/test/tests_clever.py
@@ -1,4 +1,4 @@
-#!/usr/bin/env python
+#!/usr/bin/env python3
# test backwards compatibility
diff --git a/builder/test/tests_py2.py b/builder/test/tests_py2.py
new file mode 100755
index 000000000..32c389f2b
--- /dev/null
+++ b/builder/test/tests_py2.py
@@ -0,0 +1,7 @@
+#!/usr/bin/env python
+
+# Make sure our Python 2 software is installed
+
+import cv2
+
+print(cv2.getBuildInformation())
diff --git a/builder/test/tests_py3.py b/builder/test/tests_py3.py
deleted file mode 100755
index aca3a404d..000000000
--- a/builder/test/tests_py3.py
+++ /dev/null
@@ -1,7 +0,0 @@
-#!/usr/bin/env python3
-
-# Make sure our Python 3 software is installed
-
-import cv2
-
-print(cv2.getBuildInformation())
diff --git a/clover/package.xml b/clover/package.xml
index 8a9a0c7ed..80a8b4d60 100644
--- a/clover/package.xml
+++ b/clover/package.xml
@@ -1,5 +1,5 @@
-
+
clover
0.0.1
The Clover package
@@ -37,8 +37,10 @@
rosbridge_server
web_video_server
tf2_web_republisher
- python-lxml
- python-pymavlink
+ python-lxml
+ python3-lxml
+ python-pymavlink
+ python-pymavlink
diff --git a/clover/requirements.txt b/clover/requirements.txt
index 941741885..27eac3129 100644
--- a/clover/requirements.txt
+++ b/clover/requirements.txt
@@ -1,5 +1,5 @@
flask==1.1.1
docopt==0.6.2
-geopy==1.11.0
-smbus2==0.2.1
-VL53L1X==0.0.2
+geopy==1.20.0
+smbus2==0.3.0
+VL53L1X==0.0.4
diff --git a/clover/src/selfcheck.py b/clover/src/selfcheck.py
index bdf7cb8e5..a4a138850 100755
--- a/clover/src/selfcheck.py
+++ b/clover/src/selfcheck.py
@@ -1,4 +1,4 @@
-#!/usr/bin/env python
+#!/usr/bin/env python3
# coding=utf-8
# Copyright (C) 2018 Copter Express Technologies
@@ -138,7 +138,7 @@ def mavlink_exec(cmd, timeout=3.0):
timeout=3,
baudrate=0,
count=len(cmd),
- data=map(ord, cmd.ljust(70, '\0')))
+ data=[ord(c) for c in cmd.ljust(70, '\0')])
msg.pack(link)
ros_msg = mavlink.convert_to_rosmsg(msg)
mavlink_pub.publish(ros_msg)
@@ -609,7 +609,7 @@ def check_rangefinder():
@check('Boot duration')
def check_boot_duration():
- output = subprocess.check_output('systemd-analyze')
+ output = subprocess.check_output('systemd-analyze').decode()
r = re.compile(r'([\d\.]+)s\s*$', flags=re.MULTILINE)
duration = float(r.search(output).groups()[0])
if duration > 15:
@@ -620,7 +620,7 @@ def check_boot_duration():
def check_cpu_usage():
WHITELIST = 'nodelet',
CMD = "top -n 1 -b -i | tail -n +8 | awk '{ printf(\"%-8s\\t%-8s\\t%-8s\\n\", $1, $9, $12); }'"
- output = subprocess.check_output(CMD, shell=True)
+ output = subprocess.check_output(CMD, shell=True).decode()
processes = output.split('\n')
for process in processes:
if not process:
@@ -636,7 +636,7 @@ def check_cpu_usage():
def check_clover_service():
try:
output = subprocess.check_output('systemctl show -p ActiveState --value clover.service'.split(),
- stderr=subprocess.STDOUT)
+ stderr=subprocess.STDOUT).decode()
except subprocess.CalledProcessError as e:
failure('systemctl returned %s: %s', e.returncode, e.output)
return
@@ -751,7 +751,7 @@ def check_rpi_health():
# =
# In case of `get_throttled`, is a hexadecimal number
# with some of the FLAGs OR'ed together
- output = subprocess.check_output(['vcgencmd', 'get_throttled'])
+ output = subprocess.check_output(['vcgencmd', 'get_throttled']).decode()
except OSError:
failure('could not call vcgencmd binary; not a Raspberry Pi?')
return
diff --git a/clover/test/basic.py b/clover/test/basic.py
index fe546f7d1..b4ba870d2 100755
--- a/clover/test/basic.py
+++ b/clover/test/basic.py
@@ -1,4 +1,3 @@
-#!/usr/bin/env python
import rospy
import pytest
from mavros_msgs.msg import State
diff --git a/clover/www/js/ros3d.js b/clover/www/js/ros3d.js
index 2a607c253..ed82246bc 100644
--- a/clover/www/js/ros3d.js
+++ b/clover/www/js/ros3d.js
@@ -1,3388 +1,55170 @@
-/**
- * @author Russell Toris - rctoris@wpi.edu
- * @author David Gossow - dgossow@willowgarage.com
- */
+var ROS3D = (function (exports,ROSLIB) {
+'use strict';
-var ROS3D = ROS3D || {
- REVISION : '0.15.0'
-};
+// Polyfills
-// Marker types
-ROS3D.MARKER_ARROW = 0;
-ROS3D.MARKER_CUBE = 1;
-ROS3D.MARKER_SPHERE = 2;
-ROS3D.MARKER_CYLINDER = 3;
-ROS3D.MARKER_LINE_STRIP = 4;
-ROS3D.MARKER_LINE_LIST = 5;
-ROS3D.MARKER_CUBE_LIST = 6;
-ROS3D.MARKER_SPHERE_LIST = 7;
-ROS3D.MARKER_POINTS = 8;
-ROS3D.MARKER_TEXT_VIEW_FACING = 9;
-ROS3D.MARKER_MESH_RESOURCE = 10;
-ROS3D.MARKER_TRIANGLE_LIST = 11;
+if ( Number.EPSILON === undefined ) {
-// Interactive marker feedback types
-ROS3D.INTERACTIVE_MARKER_KEEP_ALIVE = 0;
-ROS3D.INTERACTIVE_MARKER_POSE_UPDATE = 1;
-ROS3D.INTERACTIVE_MARKER_MENU_SELECT = 2;
-ROS3D.INTERACTIVE_MARKER_BUTTON_CLICK = 3;
-ROS3D.INTERACTIVE_MARKER_MOUSE_DOWN = 4;
-ROS3D.INTERACTIVE_MARKER_MOUSE_UP = 5;
+ Number.EPSILON = Math.pow( 2, - 52 );
-// Interactive marker control types
-ROS3D.INTERACTIVE_MARKER_NONE = 0;
-ROS3D.INTERACTIVE_MARKER_MENU = 1;
-ROS3D.INTERACTIVE_MARKER_BUTTON = 2;
-ROS3D.INTERACTIVE_MARKER_MOVE_AXIS = 3;
-ROS3D.INTERACTIVE_MARKER_MOVE_PLANE = 4;
-ROS3D.INTERACTIVE_MARKER_ROTATE_AXIS = 5;
-ROS3D.INTERACTIVE_MARKER_MOVE_ROTATE = 6;
+}
-// Interactive marker rotation behavior
-ROS3D.INTERACTIVE_MARKER_INHERIT = 0;
-ROS3D.INTERACTIVE_MARKER_FIXED = 1;
-ROS3D.INTERACTIVE_MARKER_VIEW_FACING = 2;
+if ( Number.isInteger === undefined ) {
-// Collada loader types
-ROS3D.COLLADA_LOADER = 1;
-ROS3D.COLLADA_LOADER_2 = 2;
+ // Missing in IE
+ // https://developer.mozilla.org/en-US/docs/Web/JavaScript/Reference/Global_Objects/Number/isInteger
+ Number.isInteger = function ( value ) {
-/**
- * Create a THREE material based on the given RGBA values.
- *
- * @param r - the red value
- * @param g - the green value
- * @param b - the blue value
- * @param a - the alpha value
- * @returns the THREE material
- */
-ROS3D.makeColorMaterial = function(r, g, b, a) {
- var color = new THREE.Color();
- color.setRGB(r, g, b);
- if (a <= 0.99) {
- return new THREE.MeshBasicMaterial({
- color : color.getHex(),
- opacity : a + 0.1,
- transparent : true,
- depthWrite : true,
- blendSrc : THREE.SrcAlphaFactor,
- blendDst : THREE.OneMinusSrcAlphaFactor,
- blendEquation : THREE.ReverseSubtractEquation,
- blending : THREE.NormalBlending
- });
- } else {
- return new THREE.MeshPhongMaterial({
- color : color.getHex(),
- opacity : a,
- blending : THREE.NormalBlending
- });
- }
-};
+ return typeof value === 'number' && isFinite( value ) && Math.floor( value ) === value;
-/**
- * Return the intersection between the mouseray and the plane.
- *
- * @param mouseRay - the mouse ray
- * @param planeOrigin - the origin of the plane
- * @param planeNormal - the normal of the plane
- * @returns the intersection point
- */
-ROS3D.intersectPlane = function(mouseRay, planeOrigin, planeNormal) {
- var vector = new THREE.Vector3();
- var intersectPoint = new THREE.Vector3();
- vector.subVectors(planeOrigin, mouseRay.origin);
- var dot = mouseRay.direction.dot(planeNormal);
+ };
- // bail if ray and plane are parallel
- if (Math.abs(dot) < mouseRay.precision) {
- return undefined;
- }
+}
- // calc distance to plane
- var scalar = planeNormal.dot(vector) / dot;
+//
- intersectPoint.addVectors(mouseRay.origin, mouseRay.direction.clone().multiplyScalar(scalar));
- return intersectPoint;
-};
+if ( Math.sign === undefined ) {
-/**
- * Find the closest point on targetRay to any point on mouseRay. Math taken from
- * http://paulbourke.net/geometry/lineline3d/
- *
- * @param targetRay - the target ray to use
- * @param mouseRay - the mouse ray
- * @param the closest point between the two rays
- */
-ROS3D.findClosestPoint = function(targetRay, mouseRay) {
- var v13 = new THREE.Vector3();
- v13.subVectors(targetRay.origin, mouseRay.origin);
- var v43 = mouseRay.direction.clone();
- var v21 = targetRay.direction.clone();
- var d1343 = v13.dot(v43);
- var d4321 = v43.dot(v21);
- var d1321 = v13.dot(v21);
- var d4343 = v43.dot(v43);
- var d2121 = v21.dot(v21);
+ // https://developer.mozilla.org/en-US/docs/Web/JavaScript/Reference/Global_Objects/Math/sign
- var denom = d2121 * d4343 - d4321 * d4321;
- // check within a delta
- if (Math.abs(denom) <= 0.0001) {
- return undefined;
- }
- var numer = d1343 * d4321 - d1321 * d4343;
+ Math.sign = function ( x ) {
- var mua = numer / denom;
- return mua;
-};
+ return ( x < 0 ) ? - 1 : ( x > 0 ) ? 1 : + x;
-/**
- * Find the closest point between the axis and the mouse.
- *
- * @param axisRay - the ray from the axis
- * @param camera - the camera to project from
- * @param mousePos - the mouse position
- * @returns the closest axis point
- */
-ROS3D.closestAxisPoint = function(axisRay, camera, mousePos) {
- var projector = new THREE.Projector();
+ };
- // project axis onto screen
- var o = axisRay.origin.clone();
- projector.projectVector(o, camera);
- var o2 = axisRay.direction.clone().add(axisRay.origin);
- projector.projectVector(o2, camera);
+}
- // d is the axis vector in screen space (d = o2-o)
- var d = o2.clone().sub(o);
+if ( 'name' in Function.prototype === false ) {
- // t is the 2d ray param of perpendicular projection of mousePos onto o
- var tmp = new THREE.Vector2();
- // (t = (mousePos - o) * d / (d*d))
- var t = tmp.subVectors(mousePos, o).dot(d) / d.dot(d);
+ // Missing in IE
+ // https://developer.mozilla.org/en-US/docs/Web/JavaScript/Reference/Global_Objects/Function/name
- // mp is the final 2d-projected mouse pos (mp = o + d*t)
- var mp = new THREE.Vector2();
- mp.addVectors(o, d.clone().multiplyScalar(t));
+ Object.defineProperty( Function.prototype, 'name', {
- // go back to 3d by shooting a ray
- var vector = new THREE.Vector3(mp.x, mp.y, 0.5);
- projector.unprojectVector(vector, camera);
- var mpRay = new THREE.Ray(camera.position, vector.sub(camera.position).normalize());
+ get: function () {
- return ROS3D.findClosestPoint(axisRay, mpRay);
-};
+ return this.toString().match( /^\s*function\s*([^\(\s]*)/ )[ 1 ];
-/**
- * @author Julius Kammerl - jkammerl@willowgarage.com
- */
+ }
-/**
- * The DepthCloud object.
- *
- * @constructor
- * @param options - object with following keys:
- *
- * * url - the URL of the stream
- * * f (optional) - the camera's focal length (defaults to standard Kinect calibration)
- * * pointSize (optional) - point size (pixels) for rendered point cloud
- * * width (optional) - width of the video stream
- * * height (optional) - height of the video stream
- * * whiteness (optional) - blends rgb values to white (0..100)
- * * varianceThreshold (optional) - threshold for variance filter, used for compression artifact removal
- */
-ROS3D.DepthCloud = function(options) {
- options = options || {};
- THREE.Object3D.call(this);
-
- this.url = options.url;
- this.f = options.f || 526;
- this.pointSize = options.pointSize || 3;
- this.width = options.width || 1024;
- this.height = options.height || 1024;
- this.whiteness = options.whiteness || 0;
- this.varianceThreshold = options.varianceThreshold || 0.000016667;
-
- var metaLoaded = false;
- this.video = document.createElement('video');
-
- this.video.addEventListener('loadedmetadata', this.metaLoaded.bind(this), false);
-
- this.video.loop = true;
- this.video.src = this.url;
- this.video.crossOrigin = 'Anonymous';
- this.video.setAttribute('crossorigin', 'Anonymous');
-
- // define custom shaders
- this.vertex_shader = [
- 'uniform sampler2D map;',
- '',
- 'uniform float width;',
- 'uniform float height;',
- 'uniform float nearClipping, farClipping;',
- '',
- 'uniform float pointSize;',
- 'uniform float zOffset;',
- '',
- 'uniform float focallength;',
- '',
- 'varying vec2 vUvP;',
- 'varying vec2 colorP;',
- '',
- 'varying float depthVariance;',
- 'varying float maskVal;',
- '',
- 'float sampleDepth(vec2 pos)',
- ' {',
- ' float depth;',
- ' ',
- ' vec2 vUv = vec2( pos.x / (width*2.0), pos.y / (height*2.0)+0.5 );',
- ' vec2 vUv2 = vec2( pos.x / (width*2.0)+0.5, pos.y / (height*2.0)+0.5 );',
- ' ',
- ' vec4 depthColor = texture2D( map, vUv );',
- ' ',
- ' depth = ( depthColor.r + depthColor.g + depthColor.b ) / 3.0 ;',
- ' ',
- ' if (depth>0.99)',
- ' {',
- ' vec4 depthColor2 = texture2D( map, vUv2 );',
- ' float depth2 = ( depthColor2.r + depthColor2.g + depthColor2.b ) / 3.0 ;',
- ' depth = 0.99+depth2;',
- ' }',
- ' ',
- ' return depth;',
- ' }',
- '',
- 'float median(float a, float b, float c)',
- ' {',
- ' float r=a;',
- ' ',
- ' if ( (a0.5) || (vUvP.y<0.5) || (vUvP.y>0.0))',
- ' {',
- ' vec2 smp = decodeDepth(vec2(position.x, position.y));',
- ' float depth = smp.x;',
- ' depthVariance = smp.y;',
- ' ',
- ' float z = -depth;',
- ' ',
- ' pos = vec4(',
- ' ( position.x / width - 0.5 ) * z * (1000.0/focallength) * -1.0,',
- ' ( position.y / height - 0.5 ) * z * (1000.0/focallength),',
- ' (- z + zOffset / 1000.0) * 2.0,',
- ' 1.0);',
- ' ',
- ' vec2 maskP = vec2( position.x / (width*2.0), position.y / (height*2.0) );',
- ' vec4 maskColor = texture2D( map, maskP );',
- ' maskVal = ( maskColor.r + maskColor.g + maskColor.b ) / 3.0 ;',
- ' }',
- ' ',
- ' gl_PointSize = pointSize;',
- ' gl_Position = projectionMatrix * modelViewMatrix * pos;',
- ' ',
- '}'
- ].join('\n');
-
- this.fragment_shader = [
- 'uniform sampler2D map;',
- 'uniform float varianceThreshold;',
- 'uniform float whiteness;',
- '',
- 'varying vec2 vUvP;',
- 'varying vec2 colorP;',
- '',
- 'varying float depthVariance;',
- 'varying float maskVal;',
- '',
- '',
- 'void main() {',
- ' ',
- ' vec4 color;',
- ' ',
- ' if ( (depthVariance>varianceThreshold) || (maskVal>0.5) ||(vUvP.x<0.0)|| (vUvP.x>0.5) || (vUvP.y<0.5) || (vUvP.y>1.0))',
- ' { ',
- ' discard;',
- ' }',
- ' else ',
- ' {',
- ' color = texture2D( map, colorP );',
- ' ',
- ' float fader = whiteness /100.0;',
- ' ',
- ' color.r = color.r * (1.0-fader)+ fader;',
- ' ',
- ' color.g = color.g * (1.0-fader)+ fader;',
- ' ',
- ' color.b = color.b * (1.0-fader)+ fader;',
- ' ',
- ' color.a = 1.0;//smoothstep( 20000.0, -20000.0, gl_FragCoord.z / gl_FragCoord.w );',
- ' }',
- ' ',
- ' gl_FragColor = vec4( color.r, color.g, color.b, color.a );',
- ' ',
- '}'
- ].join('\n');
-};
-ROS3D.DepthCloud.prototype.__proto__ = THREE.Object3D.prototype;
-
-/**
- * Callback called when video metadata is ready
- */
-ROS3D.DepthCloud.prototype.metaLoaded = function() {
- this.metaLoaded = true;
- this.initStreamer();
-};
-
-/**
- * Callback called when video metadata is ready
- */
-ROS3D.DepthCloud.prototype.initStreamer = function() {
-
- if (this.metaLoaded) {
- this.texture = new THREE.Texture(this.video);
- this.geometry = new THREE.Geometry();
-
- for (var i = 0, l = this.width * this.height; i < l; i++) {
-
- var vertex = new THREE.Vector3();
- vertex.x = (i % this.width);
- vertex.y = Math.floor(i / this.width);
-
- this.geometry.vertices.push(vertex);
- }
-
- this.material = new THREE.ShaderMaterial({
- uniforms : {
- 'map' : {
- type : 't',
- value : this.texture
- },
- 'width' : {
- type : 'f',
- value : this.width
- },
- 'height' : {
- type : 'f',
- value : this.height
- },
- 'focallength' : {
- type : 'f',
- value : this.f
- },
- 'pointSize' : {
- type : 'f',
- value : this.pointSize
- },
- 'zOffset' : {
- type : 'f',
- value : 0
- },
- 'whiteness' : {
- type : 'f',
- value : this.whiteness
- },
- 'varianceThreshold' : {
- type : 'f',
- value : this.varianceThreshold
- }
- },
- vertexShader : this.vertex_shader,
- fragmentShader : this.fragment_shader
- });
+ } );
- this.mesh = new THREE.ParticleSystem(this.geometry, this.material);
- this.mesh.position.x = 0;
- this.mesh.position.y = 0;
- this.add(this.mesh);
+}
- var that = this;
+if ( Object.assign === undefined ) {
- setInterval(function() {
- if (that.video.readyState === that.video.HAVE_ENOUGH_DATA) {
- that.texture.needsUpdate = true;
- }
- }, 1000 / 30);
- }
-};
+ // Missing in IE
+ // https://developer.mozilla.org/en-US/docs/Web/JavaScript/Reference/Global_Objects/Object/assign
-/**
- * Start video playback
- */
-ROS3D.DepthCloud.prototype.startStream = function() {
- this.video.play();
-};
+ ( function () {
-/**
- * Stop video playback
- */
-ROS3D.DepthCloud.prototype.stopStream = function() {
- this.video.pause();
-};
+ Object.assign = function ( target ) {
-/**
- * @author David Gossow - dgossow@willowgarage.com
- */
+ if ( target === undefined || target === null ) {
-/**
- * The main interactive marker object.
- *
- * @constructor
- * @param options - object with following keys:
- *
- * * handle - the ROS3D.InteractiveMarkerHandle for this marker
- * * camera - the main camera associated with the viewer for this marker
- * * path (optional) - the base path to any meshes that will be loaded
- * * loader (optional) - the Collada loader to use (e.g., an instance of ROS3D.COLLADA_LOADER
- * ROS3D.COLLADA_LOADER_2) -- defaults to ROS3D.COLLADA_LOADER_2
- */
-ROS3D.InteractiveMarker = function(options) {
- THREE.Object3D.call(this);
- THREE.EventDispatcher.call(this);
-
- var that = this;
- options = options || {};
- var handle = options.handle;
- this.name = handle.name;
- var camera = options.camera;
- var path = options.path || '/';
- var loader = options.loader || ROS3D.COLLADA_LOADER_2;
- this.dragging = false;
-
- // set the initial pose
- this.onServerSetPose({
- pose : handle.pose
- });
-
- // information on where the drag started
- this.dragStart = {
- position : new THREE.Vector3(),
- orientation : new THREE.Quaternion(),
- positionWorld : new THREE.Vector3(),
- orientationWorld : new THREE.Quaternion(),
- event3d : {}
- };
-
- // add each control message
- handle.controls.forEach(function(controlMessage) {
- that.add(new ROS3D.InteractiveMarkerControl({
- parent : that,
- handle : handle,
- message : controlMessage,
- camera : camera,
- path : path,
- loader : loader
- }));
- });
+ throw new TypeError( 'Cannot convert undefined or null to object' );
- // check for any menus
- if (handle.menuEntries.length > 0) {
- this.menu = new ROS3D.InteractiveMarkerMenu({
- menuEntries : handle.menuEntries,
- menuFontSize : handle.menuFontSize
- });
+ }
- // forward menu select events
- this.menu.addEventListener('menu-select', function(event) {
- that.dispatchEvent(event);
- });
- }
-};
-ROS3D.InteractiveMarker.prototype.__proto__ = THREE.Object3D.prototype;
+ var output = Object( target );
-/**
- * Show the interactive marker menu associated with this marker.
- *
- * @param control - the control to use
- * @param event - the event that caused this
- */
-ROS3D.InteractiveMarker.prototype.showMenu = function(control, event) {
- if (this.menu) {
- this.menu.show(control, event);
- }
-};
+ for ( var index = 1; index < arguments.length; index ++ ) {
-/**
- * Move the axis based on the given event information.
- *
- * @param control - the control to use
- * @param origAxis - the origin of the axis
- * @param event3d - the event that caused this
- */
-ROS3D.InteractiveMarker.prototype.moveAxis = function(control, origAxis, event3d) {
- if (this.dragging) {
- var currentControlOri = control.currentControlOri;
- var axis = origAxis.clone().applyQuaternion(currentControlOri);
- // get move axis in world coords
- var originWorld = this.dragStart.event3d.intersection.point;
- var axisWorld = axis.clone().applyQuaternion(this.dragStart.orientationWorld.clone());
+ var source = arguments[ index ];
- var axisRay = new THREE.Ray(originWorld, axisWorld);
+ if ( source !== undefined && source !== null ) {
- // find closest point to mouse on axis
- var t = ROS3D.closestAxisPoint(axisRay, event3d.camera, event3d.mousePos);
+ for ( var nextKey in source ) {
- // offset from drag start position
- var p = new THREE.Vector3();
- p.addVectors(this.dragStart.position, axis.clone().applyQuaternion(this.dragStart.orientation)
- .multiplyScalar(t));
- this.setPosition(control, p);
+ if ( Object.prototype.hasOwnProperty.call( source, nextKey ) ) {
- event3d.stopPropagation();
- }
-};
+ output[ nextKey ] = source[ nextKey ];
-/**
- * Move with respect to the plane based on the contorl and event.
- *
- * @param control - the control to use
- * @param origNormal - the normal of the origin
- * @param event3d - the event that caused this
- */
-ROS3D.InteractiveMarker.prototype.movePlane = function(control, origNormal, event3d) {
- if (this.dragging) {
- var currentControlOri = control.currentControlOri;
- var normal = origNormal.clone().applyQuaternion(currentControlOri);
- // get plane params in world coords
- var originWorld = this.dragStart.event3d.intersection.point;
- var normalWorld = normal.clone().applyQuaternion(this.dragStart.orientationWorld);
+ }
- // intersect mouse ray with plane
- var intersection = ROS3D.intersectPlane(event3d.mouseRay, originWorld, normalWorld);
+ }
- // offset from drag start position
- var p = new THREE.Vector3();
- p.subVectors(intersection, originWorld);
- p.add(this.dragStart.positionWorld);
- this.setPosition(control, p);
- event3d.stopPropagation();
- }
-};
+ }
+
+ }
+
+ return output;
+
+ };
+
+ } )();
+
+}
/**
- * Rotate based on the control and event given.
- *
- * @param control - the control to use
- * @param origOrientation - the orientation of the origin
- * @param event3d - the event that caused this
+ * https://github.com/mrdoob/eventdispatcher.js/
*/
-ROS3D.InteractiveMarker.prototype.rotateAxis = function(control, origOrientation, event3d) {
- if (this.dragging) {
- control.updateMatrixWorld();
- var currentControlOri = control.currentControlOri;
- var orientation = currentControlOri.clone().multiply(origOrientation.clone());
+function EventDispatcher() {}
- var normal = (new THREE.Vector3(1, 0, 0)).applyQuaternion(orientation);
+Object.assign( EventDispatcher.prototype, {
- // get plane params in world coords
- var originWorld = this.dragStart.event3d.intersection.point;
- var normalWorld = normal.applyQuaternion(this.dragStart.orientationWorld);
+ addEventListener: function ( type, listener ) {
- // intersect mouse ray with plane
- var intersection = ROS3D.intersectPlane(event3d.mouseRay, originWorld, normalWorld);
+ if ( this._listeners === undefined ) this._listeners = {};
- // offset local origin to lie on intersection plane
- var normalRay = new THREE.Ray(this.dragStart.positionWorld, normalWorld);
- var rotOrigin = ROS3D.intersectPlane(normalRay, originWorld, normalWorld);
+ var listeners = this._listeners;
- // rotates from world to plane coords
- var orientationWorld = this.dragStart.orientationWorld.clone().multiply(orientation);
- var orientationWorldInv = orientationWorld.clone().inverse();
+ if ( listeners[ type ] === undefined ) {
- // rotate original and current intersection into local coords
- intersection.sub(rotOrigin);
- intersection.applyQuaternion(orientationWorldInv);
+ listeners[ type ] = [];
- var origIntersection = this.dragStart.event3d.intersection.point.clone();
- origIntersection.sub(rotOrigin);
- origIntersection.applyQuaternion(orientationWorldInv);
+ }
- // compute relative 2d angle
- var a1 = Math.atan2(intersection.y, intersection.z);
- var a2 = Math.atan2(origIntersection.y, origIntersection.z);
- var a = a2 - a1;
+ if ( listeners[ type ].indexOf( listener ) === - 1 ) {
- var rot = new THREE.Quaternion();
- rot.setFromAxisAngle(normal, a);
+ listeners[ type ].push( listener );
- // rotate
- this.setOrientation(control, rot.multiply(this.dragStart.orientationWorld));
+ }
- // offset from drag start position
- event3d.stopPropagation();
- }
-};
+ },
-/**
- * Dispatch the given event type.
- *
- * @param type - the type of event
- * @param control - the control to use
- */
-ROS3D.InteractiveMarker.prototype.feedbackEvent = function(type, control) {
- this.dispatchEvent({
- type : type,
- position : this.position.clone(),
- orientation : this.quaternion.clone(),
- controlName : control.name
- });
-};
+ hasEventListener: function ( type, listener ) {
-/**
- * Start a drag action.
- *
- * @param control - the control to use
- * @param event3d - the event that caused this
- */
-ROS3D.InteractiveMarker.prototype.startDrag = function(control, event3d) {
- if (event3d.domEvent.button === 0) {
- event3d.stopPropagation();
- this.dragging = true;
- this.updateMatrixWorld(true);
- var scale = new THREE.Vector3();
- this.matrixWorld
- .decompose(this.dragStart.positionWorld, this.dragStart.orientationWorld, scale);
- this.dragStart.position = this.position.clone();
- this.dragStart.orientation = this.quaternion.clone();
- this.dragStart.event3d = event3d;
-
- this.feedbackEvent('user-mousedown', control);
- }
-};
+ if ( this._listeners === undefined ) return false;
-/**
- * Stop a drag action.
- *
- * @param control - the control to use
- * @param event3d - the event that caused this
- */
-ROS3D.InteractiveMarker.prototype.stopDrag = function(control, event3d) {
- if (event3d.domEvent.button === 0) {
- event3d.stopPropagation();
- this.dragging = false;
- this.dragStart.event3d = {};
- this.onServerSetPose(this.bufferedPoseEvent);
- this.bufferedPoseEvent = undefined;
+ var listeners = this._listeners;
- this.feedbackEvent('user-mouseup', control);
- }
-};
+ return listeners[ type ] !== undefined && listeners[ type ].indexOf( listener ) !== - 1;
-/**
- * Handle a button click.
- *
- * @param control - the control to use
- * @param event3d - the event that caused this
- */
-ROS3D.InteractiveMarker.prototype.buttonClick = function(control, event3d) {
- event3d.stopPropagation();
- this.feedbackEvent('user-button-click', control);
-};
+ },
-/**
- * Handle a user pose change for the position.
- *
- * @param control - the control to use
- * @param event3d - the event that caused this
- */
-ROS3D.InteractiveMarker.prototype.setPosition = function(control, position) {
- this.position = position;
- this.feedbackEvent('user-pose-change', control);
-};
+ removeEventListener: function ( type, listener ) {
-/**
- * Handle a user pose change for the orientation.
- *
- * @param control - the control to use
- * @param event3d - the event that caused this
- */
-ROS3D.InteractiveMarker.prototype.setOrientation = function(control, orientation) {
- orientation.normalize();
- this.quaternion = orientation;
- this.feedbackEvent('user-pose-change', control);
-};
+ if ( this._listeners === undefined ) return;
-/**
- * Update the marker based when the pose is set from the server.
- *
- * @param event - the event that caused this
- */
-ROS3D.InteractiveMarker.prototype.onServerSetPose = function(event) {
- if (event !== undefined) {
- // don't update while dragging
- if (this.dragging) {
- this.bufferedPoseEvent = event;
- } else {
- var pose = event.pose;
+ var listeners = this._listeners;
+ var listenerArray = listeners[ type ];
- this.position.x = pose.position.x;
- this.position.y = pose.position.y;
- this.position.z = pose.position.z;
+ if ( listenerArray !== undefined ) {
- this.quaternion = new THREE.Quaternion(pose.orientation.x, pose.orientation.y,
- pose.orientation.z, pose.orientation.w);
+ var index = listenerArray.indexOf( listener );
- this.updateMatrixWorld(true);
- }
- }
-};
+ if ( index !== - 1 ) {
-/**
- * Free memory of elements in this marker.
- */
-ROS3D.InteractiveMarker.prototype.dispose = function() {
- var that = this;
- this.children.forEach(function(intMarkerControl) {
- intMarkerControl.children.forEach(function(marker) {
- marker.dispose();
- intMarkerControl.remove(marker);
- });
- that.remove(intMarkerControl);
- });
-};
+ listenerArray.splice( index, 1 );
-THREE.EventDispatcher.prototype.apply( ROS3D.InteractiveMarker.prototype );
+ }
-/**
- * @author David Gossow - dgossow@willowgarage.com
- */
+ }
-/**
- * A client for an interactive marker topic.
- *
- * @constructor
- * @param options - object with following keys:
- *
- * * ros - a handle to the ROS connection
- * * tfClient - a handle to the TF client
- * * topic (optional) - the topic to subscribe to, like '/basic_controls'
- * * path (optional) - the base path to any meshes that will be loaded
- * * camera - the main camera associated with the viewer for this marker client
- * * rootObject (optional) - the root THREE 3D object to render to
- * * loader (optional) - the Collada loader to use (e.g., an instance of ROS3D.COLLADA_LOADER
- * ROS3D.COLLADA_LOADER_2) -- defaults to ROS3D.COLLADA_LOADER_2
- * * menuFontSize (optional) - the menu font size
- */
-ROS3D.InteractiveMarkerClient = function(options) {
- var that = this;
- options = options || {};
- this.ros = options.ros;
- this.tfClient = options.tfClient;
- this.topic = options.topic;
- this.path = options.path || '/';
- this.camera = options.camera;
- this.rootObject = options.rootObject || new THREE.Object3D();
- this.loader = options.loader || ROS3D.COLLADA_LOADER_2;
- this.menuFontSize = options.menuFontSize || '0.8em';
-
- this.interactiveMarkers = {};
- this.updateTopic = null;
- this.feedbackTopic = null;
-
- // check for an initial topic
- if (this.topic) {
- this.subscribe(this.topic);
- }
-};
+ },
-/**
- * Subscribe to the given interactive marker topic. This will unsubscribe from any current topics.
- *
- * @param topic - the topic to subscribe to, like '/basic_controls'
- */
-ROS3D.InteractiveMarkerClient.prototype.subscribe = function(topic) {
- // unsubscribe to the other topics
- this.unsubscribe();
+ dispatchEvent: function ( event ) {
- this.updateTopic = new ROSLIB.Topic({
- ros : this.ros,
- name : topic + '/tunneled/update',
- messageType : 'visualization_msgs/InteractiveMarkerUpdate',
- compression : 'png'
- });
- this.updateTopic.subscribe(this.processUpdate.bind(this));
+ if ( this._listeners === undefined ) return;
- this.feedbackTopic = new ROSLIB.Topic({
- ros : this.ros,
- name : topic + '/feedback',
- messageType : 'visualization_msgs/InteractiveMarkerFeedback',
- compression : 'png'
- });
- this.feedbackTopic.advertise();
+ var listeners = this._listeners;
+ var listenerArray = listeners[ event.type ];
- this.initService = new ROSLIB.Service({
- ros : this.ros,
- name : topic + '/tunneled/get_init',
- serviceType : 'demo_interactive_markers/GetInit'
- });
- var request = new ROSLIB.ServiceRequest({});
- this.initService.callService(request, this.processInit.bind(this));
-};
+ if ( listenerArray !== undefined ) {
+
+ event.target = this;
+
+ var array = listenerArray.slice( 0 );
+
+ for ( var i = 0, l = array.length; i < l; i ++ ) {
+
+ array[ i ].call( this, event );
+
+ }
+
+ }
+
+ }
+
+} );
+
+var REVISION = '89';
+var MOUSE = { LEFT: 0, MIDDLE: 1, RIGHT: 2 };
+var CullFaceNone = 0;
+var CullFaceBack = 1;
+var CullFaceFront = 2;
+var CullFaceFrontBack = 3;
+var FrontFaceDirectionCW = 0;
+var FrontFaceDirectionCCW = 1;
+var BasicShadowMap = 0;
+var PCFShadowMap = 1;
+var PCFSoftShadowMap = 2;
+var FrontSide = 0;
+var BackSide = 1;
+var DoubleSide = 2;
+var FlatShading = 1;
+var SmoothShading = 2;
+var NoColors = 0;
+var FaceColors = 1;
+var VertexColors = 2;
+var NoBlending = 0;
+var NormalBlending = 1;
+var AdditiveBlending = 2;
+var SubtractiveBlending = 3;
+var MultiplyBlending = 4;
+var CustomBlending = 5;
+var AddEquation = 100;
+var SubtractEquation = 101;
+var ReverseSubtractEquation = 102;
+var MinEquation = 103;
+var MaxEquation = 104;
+var ZeroFactor = 200;
+var OneFactor = 201;
+var SrcColorFactor = 202;
+var OneMinusSrcColorFactor = 203;
+var SrcAlphaFactor = 204;
+var OneMinusSrcAlphaFactor = 205;
+var DstAlphaFactor = 206;
+var OneMinusDstAlphaFactor = 207;
+var DstColorFactor = 208;
+var OneMinusDstColorFactor = 209;
+var SrcAlphaSaturateFactor = 210;
+var NeverDepth = 0;
+var AlwaysDepth = 1;
+var LessDepth = 2;
+var LessEqualDepth = 3;
+var EqualDepth = 4;
+var GreaterEqualDepth = 5;
+var GreaterDepth = 6;
+var NotEqualDepth = 7;
+var MultiplyOperation = 0;
+var MixOperation = 1;
+var AddOperation = 2;
+var NoToneMapping = 0;
+var LinearToneMapping = 1;
+var ReinhardToneMapping = 2;
+var Uncharted2ToneMapping = 3;
+var CineonToneMapping = 4;
+var UVMapping = 300;
+var CubeReflectionMapping = 301;
+var CubeRefractionMapping = 302;
+var EquirectangularReflectionMapping = 303;
+var EquirectangularRefractionMapping = 304;
+var SphericalReflectionMapping = 305;
+var CubeUVReflectionMapping = 306;
+var CubeUVRefractionMapping = 307;
+var RepeatWrapping = 1000;
+var ClampToEdgeWrapping = 1001;
+var MirroredRepeatWrapping = 1002;
+var NearestFilter = 1003;
+var NearestMipMapNearestFilter = 1004;
+var NearestMipMapLinearFilter = 1005;
+var LinearFilter = 1006;
+var LinearMipMapNearestFilter = 1007;
+var LinearMipMapLinearFilter = 1008;
+var UnsignedByteType = 1009;
+var ByteType = 1010;
+var ShortType = 1011;
+var UnsignedShortType = 1012;
+var IntType = 1013;
+var UnsignedIntType = 1014;
+var FloatType = 1015;
+var HalfFloatType = 1016;
+var UnsignedShort4444Type = 1017;
+var UnsignedShort5551Type = 1018;
+var UnsignedShort565Type = 1019;
+var UnsignedInt248Type = 1020;
+var AlphaFormat = 1021;
+var RGBFormat = 1022;
+var RGBAFormat = 1023;
+var LuminanceFormat = 1024;
+var LuminanceAlphaFormat = 1025;
+var RGBEFormat = RGBAFormat;
+var DepthFormat = 1026;
+var DepthStencilFormat = 1027;
+var RGB_S3TC_DXT1_Format = 2001;
+var RGBA_S3TC_DXT1_Format = 2002;
+var RGBA_S3TC_DXT3_Format = 2003;
+var RGBA_S3TC_DXT5_Format = 2004;
+var RGB_PVRTC_4BPPV1_Format = 2100;
+var RGB_PVRTC_2BPPV1_Format = 2101;
+var RGBA_PVRTC_4BPPV1_Format = 2102;
+var RGBA_PVRTC_2BPPV1_Format = 2103;
+var RGB_ETC1_Format = 2151;
+var LoopOnce = 2200;
+var LoopRepeat = 2201;
+var LoopPingPong = 2202;
+var InterpolateDiscrete = 2300;
+var InterpolateLinear = 2301;
+var InterpolateSmooth = 2302;
+var ZeroCurvatureEnding = 2400;
+var ZeroSlopeEnding = 2401;
+var WrapAroundEnding = 2402;
+var TrianglesDrawMode = 0;
+var TriangleStripDrawMode = 1;
+var TriangleFanDrawMode = 2;
+var LinearEncoding = 3000;
+var sRGBEncoding = 3001;
+var GammaEncoding = 3007;
+var RGBEEncoding = 3002;
+var LogLuvEncoding = 3003;
+var RGBM7Encoding = 3004;
+var RGBM16Encoding = 3005;
+var RGBDEncoding = 3006;
+var BasicDepthPacking = 3200;
+var RGBADepthPacking = 3201;
/**
- * Unsubscribe from the current interactive marker topic.
+ * @author alteredq / http://alteredqualia.com/
+ * @author mrdoob / http://mrdoob.com/
*/
-ROS3D.InteractiveMarkerClient.prototype.unsubscribe = function() {
- if (this.updateTopic) {
- this.updateTopic.unsubscribe();
- }
- if (this.feedbackTopic) {
- this.feedbackTopic.unadvertise();
- }
- // erase all markers
- for (var intMarkerName in this.interactiveMarkers) {
- this.eraseIntMarker(intMarkerName);
- }
- this.interactiveMarkers = {};
-};
-/**
- * Process the given interactive marker initialization message.
- *
- * @param initMessage - the interactive marker initialization message to process
- */
-ROS3D.InteractiveMarkerClient.prototype.processInit = function(initMessage) {
- var message = initMessage.msg;
+var _Math = {
- // erase any old markers
- message.erases = [];
- for (var intMarkerName in this.interactiveMarkers) {
- message.erases.push(intMarkerName);
- }
- message.poses = [];
+ DEG2RAD: Math.PI / 180,
+ RAD2DEG: 180 / Math.PI,
- // treat it as an update
- this.processUpdate(message);
-};
+ generateUUID: ( function () {
-/**
- * Process the given interactive marker update message.
- *
- * @param initMessage - the interactive marker update message to process
- */
-ROS3D.InteractiveMarkerClient.prototype.processUpdate = function(message) {
- var that = this;
+ // http://stackoverflow.com/questions/105034/how-to-create-a-guid-uuid-in-javascript/21963136#21963136
- // erase any markers
- message.erases.forEach(function(name) {
- that.eraseIntMarker(name);
- });
+ var lut = [];
- // updates marker poses
- message.poses.forEach(function(poseMessage) {
- var marker = that.interactiveMarkers[poseMessage.name];
- if (marker) {
- marker.setPoseFromServer(poseMessage.pose);
- }
- });
+ for ( var i = 0; i < 256; i ++ ) {
- // add new markers
- message.markers.forEach(function(msg) {
- // get rid of anything with the same name
- var oldhandle = that.interactiveMarkers[msg.name];
- if (oldhandle) {
- that.eraseIntMarker(oldhandle.name);
- }
+ lut[ i ] = ( i < 16 ? '0' : '' ) + ( i ).toString( 16 ).toUpperCase();
- // create the handle
- var handle = new ROS3D.InteractiveMarkerHandle({
- message : msg,
- feedbackTopic : that.feedbackTopic,
- tfClient : that.tfClient,
- menuFontSize : that.menuFontSize
- });
- that.interactiveMarkers[msg.name] = handle;
-
- // create the actual marker
- var intMarker = new ROS3D.InteractiveMarker({
- handle : handle,
- camera : that.camera,
- path : that.path,
- loader : that.loader
- });
- // add it to the scene
- intMarker.name = msg.name;
- that.rootObject.add(intMarker);
-
- // listen for any pose updates from the server
- handle.on('pose', function(pose) {
- intMarker.onServerSetPose({
- pose : pose
- });
- });
+ }
- intMarker.addEventListener('user-pose-change', handle.setPoseFromClient.bind(handle));
- intMarker.addEventListener('user-mousedown', handle.onMouseDown.bind(handle));
- intMarker.addEventListener('user-mouseup', handle.onMouseUp.bind(handle));
- intMarker.addEventListener('user-button-click', handle.onButtonClick.bind(handle));
- intMarker.addEventListener('menu-select', handle.onMenuSelect.bind(handle));
+ return function () {
- // now list for any TF changes
- handle.subscribeTf();
- });
-};
+ var d0 = Math.random() * 0xffffffff | 0;
+ var d1 = Math.random() * 0xffffffff | 0;
+ var d2 = Math.random() * 0xffffffff | 0;
+ var d3 = Math.random() * 0xffffffff | 0;
+ return lut[ d0 & 0xff ] + lut[ d0 >> 8 & 0xff ] + lut[ d0 >> 16 & 0xff ] + lut[ d0 >> 24 & 0xff ] + '-' +
+ lut[ d1 & 0xff ] + lut[ d1 >> 8 & 0xff ] + '-' + lut[ d1 >> 16 & 0x0f | 0x40 ] + lut[ d1 >> 24 & 0xff ] + '-' +
+ lut[ d2 & 0x3f | 0x80 ] + lut[ d2 >> 8 & 0xff ] + '-' + lut[ d2 >> 16 & 0xff ] + lut[ d2 >> 24 & 0xff ] +
+ lut[ d3 & 0xff ] + lut[ d3 >> 8 & 0xff ] + lut[ d3 >> 16 & 0xff ] + lut[ d3 >> 24 & 0xff ];
-/**
- * Erase the interactive marker with the given name.
- *
- * @param intMarkerName - the interactive marker name to delete
- */
-ROS3D.InteractiveMarkerClient.prototype.eraseIntMarker = function(intMarkerName) {
- if (this.interactiveMarkers[intMarkerName]) {
- // remove the object
- var targetIntMarker = this.rootObject.getObjectByName(intMarkerName);
- this.rootObject.remove(targetIntMarker);
- delete this.interactiveMarkers[intMarkerName];
- targetIntMarker.dispose();
- }
-};
+ };
-/**
- * @author David Gossow - dgossow@willowgarage.com
- */
+ } )(),
-/**
- * The main marker control object for an interactive marker.
- *
- * @constructor
- * @param options - object with following keys:
- *
- * * parent - the parent of this control
- * * message - the interactive marker control message
- * * camera - the main camera associated with the viewer for this marker client
- * * path (optional) - the base path to any meshes that will be loaded
- * * loader (optional) - the Collada loader to use (e.g., an instance of ROS3D.COLLADA_LOADER
- * ROS3D.COLLADA_LOADER_2) -- defaults to ROS3D.COLLADA_LOADER_2
- */
-ROS3D.InteractiveMarkerControl = function(options) {
- var that = this;
- THREE.Object3D.call(this);
-
- options = options || {};
- this.parent = options.parent;
- var handle = options.handle;
- var message = options.message;
- this.name = message.name;
- this.camera = options.camera;
- this.path = options.path || '/';
- this.loader = options.loader || ROS3D.COLLADA_LOADER_2;
- this.dragging = false;
- this.startMousePos = new THREE.Vector2();
-
- // orientation for the control
- var controlOri = new THREE.Quaternion(message.orientation.x, message.orientation.y,
- message.orientation.z, message.orientation.w);
- controlOri.normalize();
-
- // transform x axis into local frame
- var controlAxis = new THREE.Vector3(1, 0, 0);
- controlAxis.applyQuaternion(controlOri);
-
- this.currentControlOri = new THREE.Quaternion();
-
- // determine mouse interaction
- switch (message.interaction_mode) {
- case ROS3D.INTERACTIVE_MARKER_MOVE_AXIS:
- this.addEventListener('mousemove', this.parent.moveAxis.bind(this.parent, this, controlAxis));
- this.addEventListener('touchmove', this.parent.moveAxis.bind(this.parent, this, controlAxis));
- break;
- case ROS3D.INTERACTIVE_MARKER_ROTATE_AXIS:
- this
- .addEventListener('mousemove', this.parent.rotateAxis.bind(this.parent, this, controlOri));
- break;
- case ROS3D.INTERACTIVE_MARKER_MOVE_PLANE:
- this
- .addEventListener('mousemove', this.parent.movePlane.bind(this.parent, this, controlAxis));
- break;
- case ROS3D.INTERACTIVE_MARKER_BUTTON:
- this.addEventListener('click', this.parent.buttonClick.bind(this.parent, this));
- break;
- default:
- break;
- }
+ clamp: function ( value, min, max ) {
- /**
- * Install default listeners for highlighting / dragging.
- *
- * @param event - the event to stop
- */
- function stopPropagation(event) {
- event.stopPropagation();
- }
+ return Math.max( min, Math.min( max, value ) );
- // check the mode
- if (message.interaction_mode !== ROS3D.INTERACTIVE_MARKER_NONE) {
- this.addEventListener('mousedown', this.parent.startDrag.bind(this.parent, this));
- this.addEventListener('mouseup', this.parent.stopDrag.bind(this.parent, this));
- this.addEventListener('contextmenu', this.parent.showMenu.bind(this.parent, this));
- this.addEventListener('mouseup', function(event3d) {
- if (that.startMousePos.distanceToSquared(event3d.mousePos) === 0) {
- event3d.type = 'contextmenu';
- that.dispatchEvent(event3d);
- }
- });
- this.addEventListener('mouseover', stopPropagation);
- this.addEventListener('mouseout', stopPropagation);
- this.addEventListener('click', stopPropagation);
- this.addEventListener('mousedown', function(event3d) {
- that.startMousePos = event3d.mousePos;
- });
+ },
- // touch support
- this.addEventListener('touchstart', function(event3d) {
- if (event3d.domEvent.touches.length === 1) {
- event3d.type = 'mousedown';
- event3d.domEvent.button = 0;
- that.dispatchEvent(event3d);
- }
- });
- this.addEventListener('touchmove', function(event3d) {
- if (event3d.domEvent.touches.length === 1) {
- event3d.type = 'mousemove';
- event3d.domEvent.button = 0;
- that.dispatchEvent(event3d);
- }
- });
- this.addEventListener('touchend', function(event3d) {
- if (event3d.domEvent.touches.length === 0) {
- event3d.domEvent.button = 0;
- event3d.type = 'mouseup';
- that.dispatchEvent(event3d);
- event3d.type = 'click';
- that.dispatchEvent(event3d);
- }
- });
- }
+ // compute euclidian modulo of m % n
+ // https://en.wikipedia.org/wiki/Modulo_operation
- // rotation behavior
- var rotInv = new THREE.Quaternion();
- var posInv = this.parent.position.clone().multiplyScalar(-1);
- switch (message.orientation_mode) {
- case ROS3D.INTERACTIVE_MARKER_INHERIT:
- rotInv = this.parent.quaternion.clone().inverse();
- this.updateMatrixWorld = function(force) {
- ROS3D.InteractiveMarkerControl.prototype.updateMatrixWorld.call(that, force);
- that.currentControlOri.copy(that.quaternion);
- that.currentControlOri.normalize();
- };
- break;
- case ROS3D.INTERACTIVE_MARKER_FIXED:
- this.updateMatrixWorld = function(force) {
- that.quaternion = that.parent.quaternion.clone().inverse();
- that.updateMatrix();
- that.matrixWorldNeedsUpdate = true;
- ROS3D.InteractiveMarkerControl.prototype.updateMatrixWorld.call(that, force);
- that.currentControlOri.copy(that.quaternion);
- };
- break;
- case ROS3D.INTERACTIVE_MARKER_VIEW_FACING:
- var independentMarkerOrientation = message.independent_marker_orientation;
- this.updateMatrixWorld = function(force) {
- that.camera.updateMatrixWorld();
- var cameraRot = new THREE.Matrix4().extractRotation(that.camera.matrixWorld);
+ euclideanModulo: function ( n, m ) {
- var ros2Gl = new THREE.Matrix4();
- var r90 = Math.PI * 0.5;
- var rv = new THREE.Euler(-r90, 0, r90);
- ros2Gl.makeRotationFromEuler(rv);
+ return ( ( n % m ) + m ) % m;
- var worldToLocal = new THREE.Matrix4();
- worldToLocal.getInverse(that.parent.matrixWorld);
+ },
- cameraRot.multiplyMatrices(cameraRot, ros2Gl);
- cameraRot.multiplyMatrices(worldToLocal, cameraRot);
+ // Linear mapping from range to range
- that.currentControlOri.setFromRotationMatrix(cameraRot);
+ mapLinear: function ( x, a1, a2, b1, b2 ) {
- // check the orientation
- if (!independentMarkerOrientation) {
- that.quaternion.copy(that.currentControlOri);
- that.updateMatrix();
- that.matrixWorldNeedsUpdate = true;
- }
- ROS3D.InteractiveMarkerControl.prototype.updateMatrixWorld.call(that, force);
- };
- break;
- default:
- console.error('Unkown orientation mode: ' + message.orientation_mode);
- break;
- }
+ return b1 + ( x - a1 ) * ( b2 - b1 ) / ( a2 - a1 );
- // temporary TFClient to get transformations from InteractiveMarker
- // frame to potential child Marker frames
- var localTfClient = new ROSLIB.TFClient({
- ros : handle.tfClient.ros,
- fixedFrame : handle.message.header.frame_id,
- });
-
- // create visuals (markers)
- message.markers.forEach(function(markerMsg) {
- var addMarker = function(transformMsg) {
- var markerHelper = new ROS3D.Marker({
- message : markerMsg,
- path : that.path,
- loader : that.loader
- });
-
- // if transformMsg isn't null, this was called by TFClient
- if (transformMsg !== null) {
- // get the current pose as a ROSLIB.Pose...
- var newPose = new ROSLIB.Pose({
- position : markerHelper.position,
- orientation : markerHelper.quaternion
- });
- // so we can apply the transform provided by the TFClient
- newPose.applyTransform(new ROSLIB.Transform(transformMsg));
- markerHelper.setPose(newPose);
+ },
- markerHelper.updateMatrixWorld();
- // we only need to set the pose once - at least, this is what RViz seems to be doing, might change in the future
- localTfClient.unsubscribe(markerMsg.header.frame_id);
- }
+ // https://en.wikipedia.org/wiki/Linear_interpolation
- // add the marker
- that.add(markerHelper);
- };
-
- // If the marker lives in a separate TF Frame, ask the *local* TFClient
- // for the transformation from the InteractiveMarker frame to the
- // sub-Marker frame
- if (markerMsg.header.frame_id !== '') {
- localTfClient.subscribe(markerMsg.header.frame_id, addMarker);
- }
- // If not, just add the marker without changing its pose
- else {
- addMarker(null);
- }
- });
-};
-ROS3D.InteractiveMarkerControl.prototype.__proto__ = THREE.Object3D.prototype;
+ lerp: function ( x, y, t ) {
-/**
- * @author David Gossow - dgossow@willowgarage.com
- */
+ return ( 1 - t ) * x + t * y;
-/**
- * Handle with signals for a single interactive marker.
- *
- * Emits the following events:
- *
- * * 'pose' - emitted when a new pose comes from the server
- *
- * @constructor
- * @param options - object with following keys:
- *
- * * message - the interactive marker message
- * * feedbackTopic - the ROSLIB.Topic associated with the feedback
- * * tfClient - a handle to the TF client to use
- * * menuFontSize (optional) - the menu font size
- */
-ROS3D.InteractiveMarkerHandle = function(options) {
- options = options || {};
- this.message = options.message;
- this.feedbackTopic = options.feedbackTopic;
- this.tfClient = options.tfClient;
- this.menuFontSize = options.menuFontSize || '0.8em';
- this.name = this.message.name;
- this.header = this.message.header;
- this.controls = this.message.controls;
- this.menuEntries = this.message.menu_entries;
- this.dragging = false;
- this.timeoutHandle = null;
- this.tfTransform = new ROSLIB.Transform();
- this.pose = new ROSLIB.Pose();
+ },
- // start by setting the pose
- this.setPoseFromServer(this.message.pose);
-};
-ROS3D.InteractiveMarkerHandle.prototype.__proto__ = EventEmitter2.prototype;
+ // http://en.wikipedia.org/wiki/Smoothstep
-/**
- * Subscribe to the TF associated with this interactive marker.
- */
-ROS3D.InteractiveMarkerHandle.prototype.subscribeTf = function() {
- // subscribe to tf updates if frame-fixed
- if (this.message.header.stamp.secs === 0.0 && this.message.header.stamp.nsecs === 0.0) {
- this.tfClient.subscribe(this.message.header.frame_id, this.tfUpdate.bind(this));
- }
-};
+ smoothstep: function ( x, min, max ) {
-/**
- * Emit the new pose that has come from the server.
- */
-ROS3D.InteractiveMarkerHandle.prototype.emitServerPoseUpdate = function() {
- var poseTransformed = new ROSLIB.Pose(this.pose);
- poseTransformed.applyTransform(this.tfTransform);
- this.emit('pose', poseTransformed);
-};
+ if ( x <= min ) return 0;
+ if ( x >= max ) return 1;
-/**
- * Update the pose based on the pose given by the server.
- *
- * @param poseMsg - the pose given by the server
- */
-ROS3D.InteractiveMarkerHandle.prototype.setPoseFromServer = function(poseMsg) {
- this.pose = new ROSLIB.Pose(poseMsg);
- this.emitServerPoseUpdate();
-};
+ x = ( x - min ) / ( max - min );
-/**
- * Update the pose based on the TF given by the server.
- *
- * @param transformMsg - the TF given by the server
- */
-ROS3D.InteractiveMarkerHandle.prototype.tfUpdate = function(transformMsg) {
- this.tfTransform = new ROSLIB.Transform(transformMsg);
- this.emitServerPoseUpdate();
-};
+ return x * x * ( 3 - 2 * x );
-/**
- * Set the pose from the client based on the given event.
- *
- * @param event - the event to base the change off of
- */
-ROS3D.InteractiveMarkerHandle.prototype.setPoseFromClient = function(event) {
- // apply the transform
- this.pose = new ROSLIB.Pose(event);
- var inv = this.tfTransform.clone();
- inv.rotation.invert();
- inv.translation.multiplyQuaternion(inv.rotation);
- inv.translation.x *= -1;
- inv.translation.y *= -1;
- inv.translation.z *= -1;
- this.pose.applyTransform(inv);
+ },
- // send feedback to the server
- this.sendFeedback(ROS3D.INTERACTIVE_MARKER_POSE_UPDATE, undefined, 0, event.controlName);
+ smootherstep: function ( x, min, max ) {
- // keep sending pose feedback until the mouse goes up
- if (this.dragging) {
- if (this.timeoutHandle) {
- clearTimeout(this.timeoutHandle);
- }
- this.timeoutHandle = setTimeout(this.setPoseFromClient.bind(this, event), 250);
- }
-};
+ if ( x <= min ) return 0;
+ if ( x >= max ) return 1;
-/**
- * Send the button click feedback to the server.
- *
- * @param event - the event associated with the button click
- */
-ROS3D.InteractiveMarkerHandle.prototype.onButtonClick = function(event) {
- this.sendFeedback(ROS3D.INTERACTIVE_MARKER_BUTTON_CLICK, event.clickPosition, 0,
- event.controlName);
-};
+ x = ( x - min ) / ( max - min );
-/**
- * Send the mousedown feedback to the server.
- *
- * @param event - the event associated with the mousedown
- */
-ROS3D.InteractiveMarkerHandle.prototype.onMouseDown = function(event) {
- this.sendFeedback(ROS3D.INTERACTIVE_MARKER_MOUSE_DOWN, event.clickPosition, 0, event.controlName);
- this.dragging = true;
-};
+ return x * x * x * ( x * ( x * 6 - 15 ) + 10 );
-/**
- * Send the mouseup feedback to the server.
- *
- * @param event - the event associated with the mouseup
- */
-ROS3D.InteractiveMarkerHandle.prototype.onMouseUp = function(event) {
- this.sendFeedback(ROS3D.INTERACTIVE_MARKER_MOUSE_UP, event.clickPosition, 0, event.controlName);
- this.dragging = false;
- if (this.timeoutHandle) {
- clearTimeout(this.timeoutHandle);
- }
-};
+ },
-/**
- * Send the menu select feedback to the server.
- *
- * @param event - the event associated with the menu select
- */
-ROS3D.InteractiveMarkerHandle.prototype.onMenuSelect = function(event) {
- this.sendFeedback(ROS3D.INTERACTIVE_MARKER_MENU_SELECT, undefined, event.id, event.controlName);
-};
+ // Random integer from interval
-/**
- * Send feedback to the interactive marker server.
- *
- * @param eventType - the type of event that happened
- * @param clickPosition (optional) - the position in ROS space the click happened
- * @param menuEntryID (optional) - the menu entry ID that is associated
- * @param controlName - the name of the control
- */
-ROS3D.InteractiveMarkerHandle.prototype.sendFeedback = function(eventType, clickPosition,
- menuEntryID, controlName) {
+ randInt: function ( low, high ) {
- // check for the click position
- var mousePointValid = clickPosition !== undefined;
- clickPosition = clickPosition || {
- x : 0,
- y : 0,
- z : 0
- };
+ return low + Math.floor( Math.random() * ( high - low + 1 ) );
- var feedback = {
- header : this.header,
- client_id : this.clientID,
- marker_name : this.name,
- control_name : controlName,
- event_type : eventType,
- pose : this.pose,
- mouse_point : clickPosition,
- mouse_point_valid : mousePointValid,
- menu_entry_id : menuEntryID
- };
- this.feedbackTopic.publish(feedback);
-};
+ },
-/**
- * @author David Gossow - dgossow@willowgarage.com
- */
+ // Random float from interval
-/**
- * A menu for an interactive marker. This will be overlayed on the canvas.
- *
- * @constructor
- * @param options - object with following keys:
- *
- * * menuEntries - the menu entries to add
- * * className (optional) - a custom CSS class for the menu div
- * * entryClassName (optional) - a custom CSS class for the menu entry
- * * overlayClassName (optional) - a custom CSS class for the menu overlay
- * * menuFontSize (optional) - the menu font size
- */
-ROS3D.InteractiveMarkerMenu = function(options) {
- var that = this;
- options = options || {};
- var menuEntries = options.menuEntries;
- var className = options.className || 'default-interactive-marker-menu';
- var entryClassName = options.entryClassName || 'default-interactive-marker-menu-entry';
- var overlayClassName = options.overlayClassName || 'default-interactive-marker-overlay';
- var menuFontSize = options.menuFontSize || '0.8em';
-
- // holds the menu tree
- var allMenus = [];
- allMenus[0] = {
- children : []
- };
-
- THREE.EventDispatcher.call(this);
-
- // create the CSS for this marker if it has not been created
- if (document.getElementById('default-interactive-marker-menu-css') === null) {
- var style = document.createElement('style');
- style.id = 'default-interactive-marker-menu-css';
- style.type = 'text/css';
- style.innerHTML = '.default-interactive-marker-menu {' + 'background-color: #444444;'
- + 'border: 1px solid #888888;' + 'border: 1px solid #888888;' + 'padding: 0px 0px 0px 0px;'
- + 'color: #FFFFFF;' + 'font-family: sans-serif;' + 'font-size: ' + menuFontSize +';' + 'z-index: 1002;'
- + '}' + '.default-interactive-marker-menu ul {' + 'padding: 0px 0px 5px 0px;'
- + 'margin: 0px;' + 'list-style-type: none;' + '}'
- + '.default-interactive-marker-menu ul li div {' + '-webkit-touch-callout: none;'
- + '-webkit-user-select: none;' + '-khtml-user-select: none;' + '-moz-user-select: none;'
- + '-ms-user-select: none;' + 'user-select: none;' + 'cursor: default;'
- + 'padding: 3px 10px 3px 10px;' + '}' + '.default-interactive-marker-menu-entry:hover {'
- + ' background-color: #666666;' + ' cursor: pointer;' + '}'
- + '.default-interactive-marker-menu ul ul {' + ' font-style: italic;'
- + ' padding-left: 10px;' + '}' + '.default-interactive-marker-overlay {'
- + ' position: absolute;' + ' top: 0%;' + ' left: 0%;' + ' width: 100%;'
- + ' height: 100%;' + ' background-color: black;' + ' z-index: 1001;'
- + ' -moz-opacity: 0.0;' + ' opacity: .0;' + ' filter: alpha(opacity = 0);' + '}';
- document.getElementsByTagName('head')[0].appendChild(style);
- }
+ randFloat: function ( low, high ) {
- // place the menu in a div
- this.menuDomElem = document.createElement('div');
- this.menuDomElem.style.position = 'absolute';
- this.menuDomElem.className = className;
- this.menuDomElem.addEventListener('contextmenu', function(event) {
- event.preventDefault();
- });
-
- // create the overlay DOM
- this.overlayDomElem = document.createElement('div');
- this.overlayDomElem.className = overlayClassName;
-
- this.hideListener = this.hide.bind(this);
- this.overlayDomElem.addEventListener('contextmenu', this.hideListener);
- this.overlayDomElem.addEventListener('click', this.hideListener);
- this.overlayDomElem.addEventListener('touchstart', this.hideListener);
-
- // parse all entries and link children to parents
- var i, entry, id;
- for ( i = 0; i < menuEntries.length; i++) {
- entry = menuEntries[i];
- id = entry.id;
- allMenus[id] = {
- title : entry.title,
- id : id,
- children : []
- };
- }
- for ( i = 0; i < menuEntries.length; i++) {
- entry = menuEntries[i];
- id = entry.id;
- var menu = allMenus[id];
- var parent = allMenus[entry.parent_id];
- parent.children.push(menu);
- }
+ return low + Math.random() * ( high - low );
- function emitMenuSelect(menuEntry, domEvent) {
- this.dispatchEvent({
- type : 'menu-select',
- domEvent : domEvent,
- id : menuEntry.id,
- controlName : this.controlName
- });
- this.hide(domEvent);
- }
+ },
- /**
- * Create the HTML UL element for the menu and link it to the parent.
- *
- * @param parentDomElem - the parent DOM element
- * @param parentMenu - the parent menu
- */
- function makeUl(parentDomElem, parentMenu) {
+ // Random float from <-range/2, range/2> interval
- var ulElem = document.createElement('ul');
- parentDomElem.appendChild(ulElem);
+ randFloatSpread: function ( range ) {
- var children = parentMenu.children;
+ return range * ( 0.5 - Math.random() );
- for ( var i = 0; i < children.length; i++) {
- var liElem = document.createElement('li');
- var divElem = document.createElement('div');
- divElem.appendChild(document.createTextNode(children[i].title));
- ulElem.appendChild(liElem);
- liElem.appendChild(divElem);
+ },
- if (children[i].children.length > 0) {
- makeUl(liElem, children[i]);
- divElem.addEventListener('click', that.hide.bind(that));
- divElem.addEventListener('touchstart', that.hide.bind(that));
- } else {
- divElem.addEventListener('click', emitMenuSelect.bind(that, children[i]));
- divElem.addEventListener('touchstart', emitMenuSelect.bind(that, children[i]));
- divElem.className = 'default-interactive-marker-menu-entry';
- }
- }
+ degToRad: function ( degrees ) {
- }
+ return degrees * _Math.DEG2RAD;
- // construct DOM element
- makeUl(this.menuDomElem, allMenus[0]);
-};
+ },
-/**
- * Shoe the menu DOM element.
- *
- * @param control - the control for the menu
- * @param event - the event that caused this
- */
-ROS3D.InteractiveMarkerMenu.prototype.show = function(control, event) {
- if (event && event.preventDefault) {
- event.preventDefault();
- }
+ radToDeg: function ( radians ) {
- this.controlName = control.name;
+ return radians * _Math.RAD2DEG;
- // position it on the click
- if (event.domEvent.changedTouches !== undefined) {
- // touch click
- this.menuDomElem.style.left = event.domEvent.changedTouches[0].pageX + 'px';
- this.menuDomElem.style.top = event.domEvent.changedTouches[0].pageY + 'px';
- } else {
- // mouse click
- this.menuDomElem.style.left = event.domEvent.clientX + 'px';
- this.menuDomElem.style.top = event.domEvent.clientY + 'px';
- }
- document.body.appendChild(this.overlayDomElem);
- document.body.appendChild(this.menuDomElem);
-};
+ },
-/**
- * Hide the menu DOM element.
- *
- * @param event (optional) - the event that caused this
- */
-ROS3D.InteractiveMarkerMenu.prototype.hide = function(event) {
- if (event && event.preventDefault) {
- event.preventDefault();
- }
+ isPowerOfTwo: function ( value ) {
- document.body.removeChild(this.overlayDomElem);
- document.body.removeChild(this.menuDomElem);
-};
+ return ( value & ( value - 1 ) ) === 0 && value !== 0;
-THREE.EventDispatcher.prototype.apply( ROS3D.InteractiveMarkerMenu.prototype );
+ },
-/**
- * @author Russell Toris - rctoris@wpi.edu
- */
+ ceilPowerOfTwo: function ( value ) {
-/**
- * An OccupancyGrid can convert a ROS occupancy grid message into a THREE object.
- *
- * @constructor
- * @param options - object with following keys:
- *
- * * message - the occupancy grid message
- */
-ROS3D.OccupancyGrid = function(options) {
- options = options || {};
- var message = options.message;
-
- // create the geometry
- var width = message.info.width;
- var height = message.info.height;
- var geom = new THREE.PlaneGeometry(width, height);
-
- // internal drawing canvas
- var canvas = document.createElement('canvas');
- canvas.width = width;
- canvas.height = height;
- var context = canvas.getContext('2d');
- // create the color material
- var imageData = context.createImageData(width, height);
- for ( var row = 0; row < height; row++) {
- for ( var col = 0; col < width; col++) {
- // determine the index into the map data
- var mapI = col + ((height - row - 1) * width);
- // determine the value
- var data = message.data[mapI];
- var val;
- if (data === 100) {
- val = 0;
- } else if (data === 0) {
- val = 255;
- } else {
- val = 127;
- }
+ return Math.pow( 2, Math.ceil( Math.log( value ) / Math.LN2 ) );
- // determine the index into the image data array
- var i = (col + (row * width)) * 4;
- // r
- imageData.data[i] = val;
- // g
- imageData.data[++i] = val;
- // b
- imageData.data[++i] = val;
- // a
- imageData.data[++i] = 255;
- }
- }
- context.putImageData(imageData, 0, 0);
+ },
+
+ floorPowerOfTwo: function ( value ) {
- var texture = new THREE.Texture(canvas);
- texture.needsUpdate = true;
- var material = new THREE.MeshBasicMaterial({
- map : texture
- });
- material.side = THREE.DoubleSide;
+ return Math.pow( 2, Math.floor( Math.log( value ) / Math.LN2 ) );
+
+ }
- // create the mesh
- THREE.Mesh.call(this, geom, material);
- // move the map so the corner is at 0, 0
- this.position.x = (width * message.info.resolution) / 2;
- this.position.y = (height * message.info.resolution) / 2;
- this.scale.x = message.info.resolution;
- this.scale.y = message.info.resolution;
};
-ROS3D.OccupancyGrid.prototype.__proto__ = THREE.Mesh.prototype;
/**
- * @author Russell Toris - rctoris@wpi.edu
+ * @author mrdoob / http://mrdoob.com/
+ * @author philogb / http://blog.thejit.org/
+ * @author egraether / http://egraether.com/
+ * @author zz85 / http://www.lab4games.net/zz85/blog
*/
-/**
- * An occupancy grid client that listens to a given map topic.
- *
- * Emits the following events:
- *
- * * 'change' - there was an update or change in the marker
- *
- * @constructor
- * @param options - object with following keys:
- *
- * * ros - the ROSLIB.Ros connection handle
- * * topic (optional) - the map topic to listen to
- * * continuous (optional) - if the map should be continuously loaded (e.g., for SLAM)
- * * tfClient (optional) - the TF client handle to use for a scene node
- * * rootObject (optional) - the root object to add this marker to
- */
-ROS3D.OccupancyGridClient = function(options) {
- var that = this;
- options = options || {};
- var ros = options.ros;
- var topic = options.topic || '/map';
- this.continuous = options.continuous;
- this.tfClient = options.tfClient;
- this.rootObject = options.rootObject || new THREE.Object3D();
+function Vector2( x, y ) {
- // current grid that is displayed
- this.currentGrid = null;
+ this.x = x || 0;
+ this.y = y || 0;
- // subscribe to the topic
- var rosTopic = new ROSLIB.Topic({
- ros : ros,
- name : topic,
- messageType : 'nav_msgs/OccupancyGrid',
- compression : 'png'
- });
- rosTopic.subscribe(function(message) {
- // check for an old map
- if (that.currentGrid) {
- that.rootObject.remove(that.currentGrid);
- }
+}
- var newGrid = new ROS3D.OccupancyGrid({
- message : message
- });
+Object.defineProperties( Vector2.prototype, {
- // check if we care about the scene
- if (that.tfClient) {
- that.currentGrid = new ROS3D.SceneNode({
- frameID : message.header.frame_id,
- tfClient : that.tfClient,
- object : newGrid,
- pose : message.info.origin
- });
- } else {
- that.currentGrid = newGrid;
- }
+ "width": {
- that.rootObject.add(that.currentGrid);
+ get: function () {
- that.emit('change');
+ return this.x;
- // check if we should unsubscribe
- if (!that.continuous) {
- rosTopic.unsubscribe();
- }
- });
-};
-ROS3D.OccupancyGridClient.prototype.__proto__ = EventEmitter2.prototype;
+ },
-/**
- * @author David Gossow - dgossow@willowgarage.com
- * @author Russell Toris - rctoris@wpi.edu
- */
+ set: function ( value ) {
-/**
- * A Marker can convert a ROS marker message into a THREE object.
- *
- * @constructor
- * @param options - object with following keys:
- *
- * * path - the base path or URL for any mesh files that will be loaded for this marker
- * * message - the marker message
- * * loader (optional) - the Collada loader to use (e.g., an instance of ROS3D.COLLADA_LOADER
- * ROS3D.COLLADA_LOADER_2) -- defaults to ROS3D.COLLADA_LOADER_2
- */
-ROS3D.Marker = function(options) {
- options = options || {};
- var path = options.path || '/';
- var message = options.message;
- var loader = options.loader || ROS3D.COLLADA_LOADER_2;
+ this.x = value;
- // check for a trailing '/'
- if (path.substr(path.length - 1) !== '/') {
- path += '/';
- }
+ }
- THREE.Object3D.call(this);
-
- if(message.scale) {
- this.msgScale = [message.scale.x, message.scale.y, message.scale.z];
- }
- else {
- this.msgScale = [1,1,1];
- }
- this.msgColor = message.color;
- this.msgMesh = undefined;
-
- // set the pose and get the color
- this.setPose(message.pose);
- var colorMaterial = ROS3D.makeColorMaterial(this.msgColor.r,
- this.msgColor.g, this.msgColor.b, this.msgColor.a);
-
- // create the object based on the type
- switch (message.type) {
- case ROS3D.MARKER_ARROW:
- // get the sizes for the arrow
- var len = message.scale.x;
- var headLength = len * 0.23;
- var headDiameter = message.scale.y;
- var shaftDiameter = headDiameter * 0.5;
-
- // determine the points
- var direction, p1 = null;
- if (message.points.length === 2) {
- p1 = new THREE.Vector3(message.points[0].x, message.points[0].y, message.points[0].z);
- var p2 = new THREE.Vector3(message.points[1].x, message.points[1].y, message.points[1].z);
- direction = p1.clone().negate().add(p2);
- // direction = p2 - p1;
- len = direction.length();
- headDiameter = message.scale.y;
- shaftDiameter = message.scale.x;
-
- if (message.scale.z !== 0.0) {
- headLength = message.scale.z;
- }
- }
-
- // add the marker
- this.add(new ROS3D.Arrow({
- direction : direction,
- origin : p1,
- length : len,
- headLength : headLength,
- shaftDiameter : shaftDiameter,
- headDiameter : headDiameter,
- material : colorMaterial
- }));
- break;
- case ROS3D.MARKER_CUBE:
- // set the cube dimensions
- var cubeGeom = new THREE.CubeGeometry(message.scale.x, message.scale.y, message.scale.z);
- this.add(new THREE.Mesh(cubeGeom, colorMaterial));
- break;
- case ROS3D.MARKER_SPHERE:
- // set the sphere dimensions
- var sphereGeom = new THREE.SphereGeometry(0.5);
- var sphereMesh = new THREE.Mesh(sphereGeom, colorMaterial);
- sphereMesh.scale.x = message.scale.x;
- sphereMesh.scale.y = message.scale.y;
- sphereMesh.scale.z = message.scale.z;
- this.add(sphereMesh);
- break;
- case ROS3D.MARKER_CYLINDER:
- // set the cylinder dimensions
- var cylinderGeom = new THREE.CylinderGeometry(0.5, 0.5, 1, 16, 1, false);
- var cylinderMesh = new THREE.Mesh(cylinderGeom, colorMaterial);
- cylinderMesh.quaternion.setFromAxisAngle(new THREE.Vector3(1, 0, 0), Math.PI * 0.5);
- cylinderMesh.scale = new THREE.Vector3(message.scale.x, message.scale.z, message.scale.y);
- this.add(cylinderMesh);
- break;
- case ROS3D.MARKER_LINE_STRIP:
- var lineStripGeom = new THREE.Geometry();
- var lineStripMaterial = new THREE.LineBasicMaterial({
- size : message.scale.x
- });
+ },
- // add the points
- var j;
- for ( j = 0; j < message.points.length; j++) {
- var pt = new THREE.Vector3();
- pt.x = message.points[j].x;
- pt.y = message.points[j].y;
- pt.z = message.points[j].z;
- lineStripGeom.vertices.push(pt);
- }
+ "height": {
- // determine the colors for each
- if (message.colors.length === message.points.length) {
- lineStripMaterial.vertexColors = true;
- for ( j = 0; j < message.points.length; j++) {
- var clr = new THREE.Color();
- clr.setRGB(message.colors[j].r, message.colors[j].g, message.colors[j].b);
- lineStripGeom.colors.push(clr);
- }
- } else {
- lineStripMaterial.color.setRGB(message.color.r, message.color.g, message.color.b);
- }
+ get: function () {
- // add the line
- this.add(new THREE.Line(lineStripGeom, lineStripMaterial));
- break;
- case ROS3D.MARKER_LINE_LIST:
- var lineListGeom = new THREE.Geometry();
- var lineListMaterial = new THREE.LineBasicMaterial({
- size : message.scale.x
- });
+ return this.y;
- // add the points
- var k;
- for ( k = 0; k < message.points.length; k++) {
- var v = new THREE.Vector3();
- v.x = message.points[k].x;
- v.y = message.points[k].y;
- v.z = message.points[k].z;
- lineListGeom.vertices.push(v);
- }
+ },
- // determine the colors for each
- if (message.colors.length === message.points.length) {
- lineListMaterial.vertexColors = true;
- for ( k = 0; k < message.points.length; k++) {
- var c = new THREE.Color();
- c.setRGB(message.colors[k].r, message.colors[k].g, message.colors[k].b);
- lineListGeom.colors.push(c);
- }
- } else {
- lineListMaterial.color.setRGB(message.color.r, message.color.g, message.color.b);
- }
-
- // add the line
- this.add(new THREE.Line(lineListGeom, lineListMaterial,THREE.LinePieces));
- break;
- case ROS3D.MARKER_CUBE_LIST:
- // holds the main object
- var object = new THREE.Object3D();
-
- // check if custom colors should be used
- var numPoints = message.points.length;
- var createColors = (numPoints === message.colors.length);
- // do not render giant lists
- var stepSize = Math.ceil(numPoints / 1250);
-
- // add the points
- var p, cube, curColor, newMesh;
- for (p = 0; p < numPoints; p+=stepSize) {
- cube = new THREE.CubeGeometry(message.scale.x, message.scale.y, message.scale.z);
-
- // check the color
- if(createColors) {
- curColor = ROS3D.makeColorMaterial(message.colors[p].r, message.colors[p].g, message.colors[p].b, message.colors[p].a);
- } else {
- curColor = colorMaterial;
- }
+ set: function ( value ) {
- newMesh = new THREE.Mesh(cube, curColor);
- newMesh.position.x = message.points[p].x;
- newMesh.position.y = message.points[p].y;
- newMesh.position.z = message.points[p].z;
- object.add(newMesh);
- }
+ this.y = value;
- this.add(object);
- break;
- case ROS3D.MARKER_SPHERE_LIST:
- case ROS3D.MARKER_POINTS:
- // for now, use a particle system for the lists
- var geometry = new THREE.Geometry();
- var material = new THREE.ParticleBasicMaterial({
- size : message.scale.x
- });
+ }
- // add the points
- var i;
- for ( i = 0; i < message.points.length; i++) {
- var vertex = new THREE.Vector3();
- vertex.x = message.points[i].x;
- vertex.y = message.points[i].y;
- vertex.z = message.points[i].z;
- geometry.vertices.push(vertex);
- }
+ }
- // determine the colors for each
- if (message.colors.length === message.points.length) {
- material.vertexColors = true;
- for ( i = 0; i < message.points.length; i++) {
- var color = new THREE.Color();
- color.setRGB(message.colors[i].r, message.colors[i].g, message.colors[i].b);
- geometry.colors.push(color);
- }
- } else {
- material.color.setRGB(message.color.r, message.color.g, message.color.b);
- }
-
- // add the particle system
- this.add(new THREE.ParticleSystem(geometry, material));
- break;
- case ROS3D.MARKER_TEXT_VIEW_FACING:
- // only work on non-empty text
- if (message.text.length > 0) {
- // Use a THREE.Sprite to always be view-facing
- // ( code from http://stackoverflow.com/a/27348780 )
- var textColor = this.msgColor;
-
- var canvas = document.createElement('canvas');
- var context = canvas.getContext('2d');
- var textHeight = 100;
- var fontString = 'normal ' + textHeight + 'px sans-serif';
- context.font = fontString;
- var metrics = context.measureText( message.text );
- var textWidth = metrics.width;
-
- canvas.width = textWidth;
- // To account for overhang (like the letter 'g'), make the canvas bigger
- // The non-text portion is transparent anyway
- canvas.height = 1.5 * textHeight;
-
- // this does need to be set again
- context.font = fontString;
- context.fillStyle = 'rgba('
- + textColor.r + ', '
- + textColor.g + ', '
- + textColor.b + ', '
- + textColor.a + ')';
- context.textAlign = 'left';
- context.textBaseline = 'middle';
- context.fillText( message.text, 0, canvas.height/2);
-
- var texture = new THREE.Texture(canvas);
- texture.needsUpdate = true;
-
- var spriteMaterial = new THREE.SpriteMaterial({
- map: texture,
- // NOTE: This is needed for THREE.js r61, unused in r70
- useScreenCoordinates: false });
- var sprite = new THREE.Sprite( spriteMaterial );
- var textSize = message.scale.x;
- sprite.scale.set(textWidth / canvas.height * textSize, textSize, 1);
-
- this.add(sprite); }
- break;
- case ROS3D.MARKER_MESH_RESOURCE:
- // load and add the mesh
- var meshColorMaterial = null;
- if(message.color.r !== 0 || message.color.g !== 0 ||
- message.color.b !== 0 || message.color.a !== 0) {
- meshColorMaterial = colorMaterial;
- }
- this.msgMesh = message.mesh_resource.substr(10);
- var meshResource = new ROS3D.MeshResource({
- path : path,
- resource : this.msgMesh,
- material : meshColorMaterial,
- loader : loader
- });
- this.add(meshResource);
- break;
- case ROS3D.MARKER_TRIANGLE_LIST:
- // create the list of triangles
- var tri = new ROS3D.TriangleList({
- material : colorMaterial,
- vertices : message.points,
- colors : message.colors
- });
- tri.scale = new THREE.Vector3(message.scale.x, message.scale.y, message.scale.z);
- this.add(tri);
- break;
- default:
- console.error('Currently unsupported marker type: ' + message.type);
- break;
- }
-};
-ROS3D.Marker.prototype.__proto__ = THREE.Object3D.prototype;
+} );
-/**
- * Set the pose of this marker to the given values.
- *
- * @param pose - the pose to set for this marker
- */
-ROS3D.Marker.prototype.setPose = function(pose) {
- // set position information
- this.position.x = pose.position.x;
- this.position.y = pose.position.y;
- this.position.z = pose.position.z;
+Object.assign( Vector2.prototype, {
- // set the rotation
- this.quaternion = new THREE.Quaternion(pose.orientation.x, pose.orientation.y,
- pose.orientation.z, pose.orientation.w);
- this.quaternion.normalize();
+ isVector2: true,
- // update the world
- this.updateMatrixWorld();
-};
+ set: function ( x, y ) {
-/**
- * Update this marker.
- *
- * @param message - the marker message
- * @return true on success otherwhise false is returned
- */
-ROS3D.Marker.prototype.update = function(message) {
- // set the pose and get the color
- this.setPose(message.pose);
-
- // Update color
- if(message.color.r !== this.msgColor.r ||
- message.color.g !== this.msgColor.g ||
- message.color.b !== this.msgColor.b ||
- message.color.a !== this.msgColor.a)
- {
- var colorMaterial = ROS3D.makeColorMaterial(
- message.color.r, message.color.g,
- message.color.b, message.color.a);
-
- switch (message.type) {
- case ROS3D.MARKER_LINE_STRIP:
- case ROS3D.MARKER_LINE_LIST:
- case ROS3D.MARKER_POINTS:
- break;
- case ROS3D.MARKER_ARROW:
- case ROS3D.MARKER_CUBE:
- case ROS3D.MARKER_SPHERE:
- case ROS3D.MARKER_CYLINDER:
- case ROS3D.MARKER_TRIANGLE_LIST:
- case ROS3D.MARKER_TEXT_VIEW_FACING:
- this.traverse (function (child){
- if (child instanceof THREE.Mesh) {
- child.material = colorMaterial;
- }
- });
- break;
- case ROS3D.MARKER_MESH_RESOURCE:
- var meshColorMaterial = null;
- if(message.color.r !== 0 || message.color.g !== 0 ||
- message.color.b !== 0 || message.color.a !== 0) {
- meshColorMaterial = this.colorMaterial;
- }
- this.traverse (function (child){
- if (child instanceof THREE.Mesh) {
- child.material = meshColorMaterial;
- }
- });
- break;
- case ROS3D.MARKER_CUBE_LIST:
- case ROS3D.MARKER_SPHERE_LIST:
- // TODO Support to update color for MARKER_CUBE_LIST & MARKER_SPHERE_LIST
- return false;
- default:
- return false;
- }
-
- this.msgColor = message.color;
- }
-
- // Update geometry
- var scaleChanged =
- Math.abs(this.msgScale[0] - message.scale.x) > 1.0e-6 ||
- Math.abs(this.msgScale[1] - message.scale.y) > 1.0e-6 ||
- Math.abs(this.msgScale[2] - message.scale.z) > 1.0e-6;
- this.msgScale = [message.scale.x, message.scale.y, message.scale.z];
-
- switch (message.type) {
- case ROS3D.MARKER_CUBE:
- case ROS3D.MARKER_SPHERE:
- case ROS3D.MARKER_CYLINDER:
- if(scaleChanged) {
- return false;
- }
- break;
- case ROS3D.MARKER_TEXT_VIEW_FACING:
- if(scaleChanged || this.text !== message.text) {
- return false;
- }
- break;
- case ROS3D.MARKER_MESH_RESOURCE:
- var meshResource = message.mesh_resource.substr(10);
- if(meshResource !== this.msgMesh) {
- return false;
- }
- if(scaleChanged) {
- return false;
- }
- break;
- case ROS3D.MARKER_ARROW:
- case ROS3D.MARKER_LINE_STRIP:
- case ROS3D.MARKER_LINE_LIST:
- case ROS3D.MARKER_CUBE_LIST:
- case ROS3D.MARKER_SPHERE_LIST:
- case ROS3D.MARKER_POINTS:
- case ROS3D.MARKER_TRIANGLE_LIST:
- // TODO: Check if geometry changed
- return false;
- default:
- break;
- }
-
- return true;
-};
+ this.x = x;
+ this.y = y;
-/*
- * Free memory of elements in this marker.
- */
-ROS3D.Marker.prototype.dispose = function() {
- this.children.forEach(function(element) {
- if (element instanceof ROS3D.MeshResource) {
- element.children.forEach(function(scene) {
- if (scene.material !== undefined) {
- scene.material.dispose();
- }
- scene.children.forEach(function(mesh) {
- if (mesh.geometry !== undefined) {
- mesh.geometry.dispose();
- }
- if (mesh.material !== undefined) {
- mesh.material.dispose();
- }
- scene.remove(mesh);
- });
- element.remove(scene);
- });
- } else {
- if (element.geometry !== undefined) {
- element.geometry.dispose();
- }
- if (element.material !== undefined) {
- element.material.dispose();
- }
- }
- element.parent.remove(element);
- });
-};
+ return this;
-/**
- * @author Russell Toris - rctoris@wpi.edu
- * @author Nils Berg - berg.nils@gmail.com
- */
+ },
-/**
- * A MarkerArray client that listens to a given topic.
- *
- * Emits the following events:
- *
- * * 'change' - there was an update or change in the MarkerArray
- *
- * @constructor
- * @param options - object with following keys:
- *
- * * ros - the ROSLIB.Ros connection handle
- * * topic - the marker topic to listen to
- * * tfClient - the TF client handle to use
- * * rootObject (optional) - the root object to add the markers to
- * * path (optional) - the base path to any meshes that will be loaded
- * * loader (optional) - the Collada loader to use (e.g., an instance of ROS3D.COLLADA_LOADER
- * ROS3D.COLLADA_LOADER_2) -- defaults to ROS3D.COLLADA_LOADER_2
- */
-ROS3D.MarkerArrayClient = function(options) {
- var that = this;
- options = options || {};
- var ros = options.ros;
- var topic = options.topic;
- this.tfClient = options.tfClient;
- this.rootObject = options.rootObject || new THREE.Object3D();
- this.path = options.path || '/';
- this.loader = options.loader || ROS3D.COLLADA_LOADER_2;
+ setScalar: function ( scalar ) {
- // Markers that are displayed (Map ns+id--Marker)
- this.markers = {};
+ this.x = scalar;
+ this.y = scalar;
- // subscribe to MarkerArray topic
- var arrayTopic = new ROSLIB.Topic({
- ros : ros,
- name : topic,
- messageType : 'visualization_msgs/MarkerArray',
- compression : 'png'
- });
-
- arrayTopic.subscribe(function(arrayMessage) {
+ return this;
- arrayMessage.markers.forEach(function(message) {
- if(message.action === 0) {
- var updated = false;
- if(message.ns + message.id in that.markers) { // "MODIFY"
- updated = that.markers[message.ns + message.id].children[0].update(message);
- if(!updated) { // "REMOVE"
- that.rootObject.remove(that.markers[message.ns + message.id]);
- }
- }
- if(!updated) { // "ADD"
- var newMarker = new ROS3D.Marker({
- message : message,
- path : that.path,
- loader : that.loader
- });
- that.markers[message.ns + message.id] = new ROS3D.SceneNode({
- frameID : message.header.frame_id,
- tfClient : that.tfClient,
- object : newMarker
- });
- that.rootObject.add(that.markers[message.ns + message.id]);
- }
- }
- else if(message.action === 1) { // "DEPRECATED"
- console.warn('Received marker message with deprecated action identifier "1"');
- }
- else if(message.action === 2) { // "DELETE"
- that.rootObject.remove(that.markers[message.ns + message.id]);
- delete that.markers[message.ns + message.id];
+ },
+
+ setX: function ( x ) {
+
+ this.x = x;
+
+ return this;
+
+ },
+
+ setY: function ( y ) {
+
+ this.y = y;
+
+ return this;
+
+ },
+
+ setComponent: function ( index, value ) {
+
+ switch ( index ) {
+
+ case 0: this.x = value; break;
+ case 1: this.y = value; break;
+ default: throw new Error( 'index is out of range: ' + index );
+
+ }
+
+ return this;
+
+ },
+
+ getComponent: function ( index ) {
+
+ switch ( index ) {
+
+ case 0: return this.x;
+ case 1: return this.y;
+ default: throw new Error( 'index is out of range: ' + index );
+
+ }
+
+ },
+
+ clone: function () {
+
+ return new this.constructor( this.x, this.y );
+
+ },
+
+ copy: function ( v ) {
+
+ this.x = v.x;
+ this.y = v.y;
+
+ return this;
+
+ },
+
+ add: function ( v, w ) {
+
+ if ( w !== undefined ) {
+
+ console.warn( 'THREE.Vector2: .add() now only accepts one argument. Use .addVectors( a, b ) instead.' );
+ return this.addVectors( v, w );
+
+ }
+
+ this.x += v.x;
+ this.y += v.y;
+
+ return this;
+
+ },
+
+ addScalar: function ( s ) {
+
+ this.x += s;
+ this.y += s;
+
+ return this;
+
+ },
+
+ addVectors: function ( a, b ) {
+
+ this.x = a.x + b.x;
+ this.y = a.y + b.y;
+
+ return this;
+
+ },
+
+ addScaledVector: function ( v, s ) {
+
+ this.x += v.x * s;
+ this.y += v.y * s;
+
+ return this;
+
+ },
+
+ sub: function ( v, w ) {
+
+ if ( w !== undefined ) {
+
+ console.warn( 'THREE.Vector2: .sub() now only accepts one argument. Use .subVectors( a, b ) instead.' );
+ return this.subVectors( v, w );
+
+ }
+
+ this.x -= v.x;
+ this.y -= v.y;
+
+ return this;
+
+ },
+
+ subScalar: function ( s ) {
+
+ this.x -= s;
+ this.y -= s;
+
+ return this;
+
+ },
+
+ subVectors: function ( a, b ) {
+
+ this.x = a.x - b.x;
+ this.y = a.y - b.y;
+
+ return this;
+
+ },
+
+ multiply: function ( v ) {
+
+ this.x *= v.x;
+ this.y *= v.y;
+
+ return this;
+
+ },
+
+ multiplyScalar: function ( scalar ) {
+
+ this.x *= scalar;
+ this.y *= scalar;
+
+ return this;
+
+ },
+
+ divide: function ( v ) {
+
+ this.x /= v.x;
+ this.y /= v.y;
+
+ return this;
+
+ },
+
+ divideScalar: function ( scalar ) {
+
+ return this.multiplyScalar( 1 / scalar );
+
+ },
+
+ applyMatrix3: function ( m ) {
+
+ var x = this.x, y = this.y;
+ var e = m.elements;
+
+ this.x = e[ 0 ] * x + e[ 3 ] * y + e[ 6 ];
+ this.y = e[ 1 ] * x + e[ 4 ] * y + e[ 7 ];
+
+ return this;
+
+ },
+
+ min: function ( v ) {
+
+ this.x = Math.min( this.x, v.x );
+ this.y = Math.min( this.y, v.y );
+
+ return this;
+
+ },
+
+ max: function ( v ) {
+
+ this.x = Math.max( this.x, v.x );
+ this.y = Math.max( this.y, v.y );
+
+ return this;
+
+ },
+
+ clamp: function ( min, max ) {
+
+ // assumes min < max, componentwise
+
+ this.x = Math.max( min.x, Math.min( max.x, this.x ) );
+ this.y = Math.max( min.y, Math.min( max.y, this.y ) );
+
+ return this;
+
+ },
+
+ clampScalar: function () {
+
+ var min = new Vector2();
+ var max = new Vector2();
+
+ return function clampScalar( minVal, maxVal ) {
+
+ min.set( minVal, minVal );
+ max.set( maxVal, maxVal );
+
+ return this.clamp( min, max );
+
+ };
+
+ }(),
+
+ clampLength: function ( min, max ) {
+
+ var length = this.length();
+
+ return this.divideScalar( length || 1 ).multiplyScalar( Math.max( min, Math.min( max, length ) ) );
+
+ },
+
+ floor: function () {
+
+ this.x = Math.floor( this.x );
+ this.y = Math.floor( this.y );
+
+ return this;
+
+ },
+
+ ceil: function () {
+
+ this.x = Math.ceil( this.x );
+ this.y = Math.ceil( this.y );
+
+ return this;
+
+ },
+
+ round: function () {
+
+ this.x = Math.round( this.x );
+ this.y = Math.round( this.y );
+
+ return this;
+
+ },
+
+ roundToZero: function () {
+
+ this.x = ( this.x < 0 ) ? Math.ceil( this.x ) : Math.floor( this.x );
+ this.y = ( this.y < 0 ) ? Math.ceil( this.y ) : Math.floor( this.y );
+
+ return this;
+
+ },
+
+ negate: function () {
+
+ this.x = - this.x;
+ this.y = - this.y;
+
+ return this;
+
+ },
+
+ dot: function ( v ) {
+
+ return this.x * v.x + this.y * v.y;
+
+ },
+
+ lengthSq: function () {
+
+ return this.x * this.x + this.y * this.y;
+
+ },
+
+ length: function () {
+
+ return Math.sqrt( this.x * this.x + this.y * this.y );
+
+ },
+
+ manhattanLength: function () {
+
+ return Math.abs( this.x ) + Math.abs( this.y );
+
+ },
+
+ normalize: function () {
+
+ return this.divideScalar( this.length() || 1 );
+
+ },
+
+ angle: function () {
+
+ // computes the angle in radians with respect to the positive x-axis
+
+ var angle = Math.atan2( this.y, this.x );
+
+ if ( angle < 0 ) angle += 2 * Math.PI;
+
+ return angle;
+
+ },
+
+ distanceTo: function ( v ) {
+
+ return Math.sqrt( this.distanceToSquared( v ) );
+
+ },
+
+ distanceToSquared: function ( v ) {
+
+ var dx = this.x - v.x, dy = this.y - v.y;
+ return dx * dx + dy * dy;
+
+ },
+
+ manhattanDistanceTo: function ( v ) {
+
+ return Math.abs( this.x - v.x ) + Math.abs( this.y - v.y );
+
+ },
+
+ setLength: function ( length ) {
+
+ return this.normalize().multiplyScalar( length );
+
+ },
+
+ lerp: function ( v, alpha ) {
+
+ this.x += ( v.x - this.x ) * alpha;
+ this.y += ( v.y - this.y ) * alpha;
+
+ return this;
+
+ },
+
+ lerpVectors: function ( v1, v2, alpha ) {
+
+ return this.subVectors( v2, v1 ).multiplyScalar( alpha ).add( v1 );
+
+ },
+
+ equals: function ( v ) {
+
+ return ( ( v.x === this.x ) && ( v.y === this.y ) );
+
+ },
+
+ fromArray: function ( array, offset ) {
+
+ if ( offset === undefined ) offset = 0;
+
+ this.x = array[ offset ];
+ this.y = array[ offset + 1 ];
+
+ return this;
+
+ },
+
+ toArray: function ( array, offset ) {
+
+ if ( array === undefined ) array = [];
+ if ( offset === undefined ) offset = 0;
+
+ array[ offset ] = this.x;
+ array[ offset + 1 ] = this.y;
+
+ return array;
+
+ },
+
+ fromBufferAttribute: function ( attribute, index, offset ) {
+
+ if ( offset !== undefined ) {
+
+ console.warn( 'THREE.Vector2: offset has been removed from .fromBufferAttribute().' );
+
+ }
+
+ this.x = attribute.getX( index );
+ this.y = attribute.getY( index );
+
+ return this;
+
+ },
+
+ rotateAround: function ( center, angle ) {
+
+ var c = Math.cos( angle ), s = Math.sin( angle );
+
+ var x = this.x - center.x;
+ var y = this.y - center.y;
+
+ this.x = x * c - y * s + center.x;
+ this.y = x * s + y * c + center.y;
+
+ return this;
+
+ }
+
+} );
+
+/**
+ * @author mrdoob / http://mrdoob.com/
+ * @author supereggbert / http://www.paulbrunt.co.uk/
+ * @author philogb / http://blog.thejit.org/
+ * @author jordi_ros / http://plattsoft.com
+ * @author D1plo1d / http://github.com/D1plo1d
+ * @author alteredq / http://alteredqualia.com/
+ * @author mikael emtinger / http://gomo.se/
+ * @author timknip / http://www.floorplanner.com/
+ * @author bhouston / http://clara.io
+ * @author WestLangley / http://github.com/WestLangley
+ */
+
+function Matrix4() {
+
+ this.elements = [
+
+ 1, 0, 0, 0,
+ 0, 1, 0, 0,
+ 0, 0, 1, 0,
+ 0, 0, 0, 1
+
+ ];
+
+ if ( arguments.length > 0 ) {
+
+ console.error( 'THREE.Matrix4: the constructor no longer reads arguments. use .set() instead.' );
+
+ }
+
+}
+
+Object.assign( Matrix4.prototype, {
+
+ isMatrix4: true,
+
+ set: function ( n11, n12, n13, n14, n21, n22, n23, n24, n31, n32, n33, n34, n41, n42, n43, n44 ) {
+
+ var te = this.elements;
+
+ te[ 0 ] = n11; te[ 4 ] = n12; te[ 8 ] = n13; te[ 12 ] = n14;
+ te[ 1 ] = n21; te[ 5 ] = n22; te[ 9 ] = n23; te[ 13 ] = n24;
+ te[ 2 ] = n31; te[ 6 ] = n32; te[ 10 ] = n33; te[ 14 ] = n34;
+ te[ 3 ] = n41; te[ 7 ] = n42; te[ 11 ] = n43; te[ 15 ] = n44;
+
+ return this;
+
+ },
+
+ identity: function () {
+
+ this.set(
+
+ 1, 0, 0, 0,
+ 0, 1, 0, 0,
+ 0, 0, 1, 0,
+ 0, 0, 0, 1
+
+ );
+
+ return this;
+
+ },
+
+ clone: function () {
+
+ return new Matrix4().fromArray( this.elements );
+
+ },
+
+ copy: function ( m ) {
+
+ var te = this.elements;
+ var me = m.elements;
+
+ te[ 0 ] = me[ 0 ]; te[ 1 ] = me[ 1 ]; te[ 2 ] = me[ 2 ]; te[ 3 ] = me[ 3 ];
+ te[ 4 ] = me[ 4 ]; te[ 5 ] = me[ 5 ]; te[ 6 ] = me[ 6 ]; te[ 7 ] = me[ 7 ];
+ te[ 8 ] = me[ 8 ]; te[ 9 ] = me[ 9 ]; te[ 10 ] = me[ 10 ]; te[ 11 ] = me[ 11 ];
+ te[ 12 ] = me[ 12 ]; te[ 13 ] = me[ 13 ]; te[ 14 ] = me[ 14 ]; te[ 15 ] = me[ 15 ];
+
+ return this;
+
+ },
+
+ copyPosition: function ( m ) {
+
+ var te = this.elements, me = m.elements;
+
+ te[ 12 ] = me[ 12 ];
+ te[ 13 ] = me[ 13 ];
+ te[ 14 ] = me[ 14 ];
+
+ return this;
+
+ },
+
+ extractBasis: function ( xAxis, yAxis, zAxis ) {
+
+ xAxis.setFromMatrixColumn( this, 0 );
+ yAxis.setFromMatrixColumn( this, 1 );
+ zAxis.setFromMatrixColumn( this, 2 );
+
+ return this;
+
+ },
+
+ makeBasis: function ( xAxis, yAxis, zAxis ) {
+
+ this.set(
+ xAxis.x, yAxis.x, zAxis.x, 0,
+ xAxis.y, yAxis.y, zAxis.y, 0,
+ xAxis.z, yAxis.z, zAxis.z, 0,
+ 0, 0, 0, 1
+ );
+
+ return this;
+
+ },
+
+ extractRotation: function () {
+
+ var v1 = new Vector3();
+
+ return function extractRotation( m ) {
+
+ var te = this.elements;
+ var me = m.elements;
+
+ var scaleX = 1 / v1.setFromMatrixColumn( m, 0 ).length();
+ var scaleY = 1 / v1.setFromMatrixColumn( m, 1 ).length();
+ var scaleZ = 1 / v1.setFromMatrixColumn( m, 2 ).length();
+
+ te[ 0 ] = me[ 0 ] * scaleX;
+ te[ 1 ] = me[ 1 ] * scaleX;
+ te[ 2 ] = me[ 2 ] * scaleX;
+
+ te[ 4 ] = me[ 4 ] * scaleY;
+ te[ 5 ] = me[ 5 ] * scaleY;
+ te[ 6 ] = me[ 6 ] * scaleY;
+
+ te[ 8 ] = me[ 8 ] * scaleZ;
+ te[ 9 ] = me[ 9 ] * scaleZ;
+ te[ 10 ] = me[ 10 ] * scaleZ;
+
+ return this;
+
+ };
+
+ }(),
+
+ makeRotationFromEuler: function ( euler ) {
+
+ if ( ! ( euler && euler.isEuler ) ) {
+
+ console.error( 'THREE.Matrix4: .makeRotationFromEuler() now expects a Euler rotation rather than a Vector3 and order.' );
+
+ }
+
+ var te = this.elements;
+
+ var x = euler.x, y = euler.y, z = euler.z;
+ var a = Math.cos( x ), b = Math.sin( x );
+ var c = Math.cos( y ), d = Math.sin( y );
+ var e = Math.cos( z ), f = Math.sin( z );
+
+ if ( euler.order === 'XYZ' ) {
+
+ var ae = a * e, af = a * f, be = b * e, bf = b * f;
+
+ te[ 0 ] = c * e;
+ te[ 4 ] = - c * f;
+ te[ 8 ] = d;
+
+ te[ 1 ] = af + be * d;
+ te[ 5 ] = ae - bf * d;
+ te[ 9 ] = - b * c;
+
+ te[ 2 ] = bf - ae * d;
+ te[ 6 ] = be + af * d;
+ te[ 10 ] = a * c;
+
+ } else if ( euler.order === 'YXZ' ) {
+
+ var ce = c * e, cf = c * f, de = d * e, df = d * f;
+
+ te[ 0 ] = ce + df * b;
+ te[ 4 ] = de * b - cf;
+ te[ 8 ] = a * d;
+
+ te[ 1 ] = a * f;
+ te[ 5 ] = a * e;
+ te[ 9 ] = - b;
+
+ te[ 2 ] = cf * b - de;
+ te[ 6 ] = df + ce * b;
+ te[ 10 ] = a * c;
+
+ } else if ( euler.order === 'ZXY' ) {
+
+ var ce = c * e, cf = c * f, de = d * e, df = d * f;
+
+ te[ 0 ] = ce - df * b;
+ te[ 4 ] = - a * f;
+ te[ 8 ] = de + cf * b;
+
+ te[ 1 ] = cf + de * b;
+ te[ 5 ] = a * e;
+ te[ 9 ] = df - ce * b;
+
+ te[ 2 ] = - a * d;
+ te[ 6 ] = b;
+ te[ 10 ] = a * c;
+
+ } else if ( euler.order === 'ZYX' ) {
+
+ var ae = a * e, af = a * f, be = b * e, bf = b * f;
+
+ te[ 0 ] = c * e;
+ te[ 4 ] = be * d - af;
+ te[ 8 ] = ae * d + bf;
+
+ te[ 1 ] = c * f;
+ te[ 5 ] = bf * d + ae;
+ te[ 9 ] = af * d - be;
+
+ te[ 2 ] = - d;
+ te[ 6 ] = b * c;
+ te[ 10 ] = a * c;
+
+ } else if ( euler.order === 'YZX' ) {
+
+ var ac = a * c, ad = a * d, bc = b * c, bd = b * d;
+
+ te[ 0 ] = c * e;
+ te[ 4 ] = bd - ac * f;
+ te[ 8 ] = bc * f + ad;
+
+ te[ 1 ] = f;
+ te[ 5 ] = a * e;
+ te[ 9 ] = - b * e;
+
+ te[ 2 ] = - d * e;
+ te[ 6 ] = ad * f + bc;
+ te[ 10 ] = ac - bd * f;
+
+ } else if ( euler.order === 'XZY' ) {
+
+ var ac = a * c, ad = a * d, bc = b * c, bd = b * d;
+
+ te[ 0 ] = c * e;
+ te[ 4 ] = - f;
+ te[ 8 ] = d * e;
+
+ te[ 1 ] = ac * f + bd;
+ te[ 5 ] = a * e;
+ te[ 9 ] = ad * f - bc;
+
+ te[ 2 ] = bc * f - ad;
+ te[ 6 ] = b * e;
+ te[ 10 ] = bd * f + ac;
+
+ }
+
+ // last column
+ te[ 3 ] = 0;
+ te[ 7 ] = 0;
+ te[ 11 ] = 0;
+
+ // bottom row
+ te[ 12 ] = 0;
+ te[ 13 ] = 0;
+ te[ 14 ] = 0;
+ te[ 15 ] = 1;
+
+ return this;
+
+ },
+
+ makeRotationFromQuaternion: function ( q ) {
+
+ var te = this.elements;
+
+ var x = q._x, y = q._y, z = q._z, w = q._w;
+ var x2 = x + x, y2 = y + y, z2 = z + z;
+ var xx = x * x2, xy = x * y2, xz = x * z2;
+ var yy = y * y2, yz = y * z2, zz = z * z2;
+ var wx = w * x2, wy = w * y2, wz = w * z2;
+
+ te[ 0 ] = 1 - ( yy + zz );
+ te[ 4 ] = xy - wz;
+ te[ 8 ] = xz + wy;
+
+ te[ 1 ] = xy + wz;
+ te[ 5 ] = 1 - ( xx + zz );
+ te[ 9 ] = yz - wx;
+
+ te[ 2 ] = xz - wy;
+ te[ 6 ] = yz + wx;
+ te[ 10 ] = 1 - ( xx + yy );
+
+ // last column
+ te[ 3 ] = 0;
+ te[ 7 ] = 0;
+ te[ 11 ] = 0;
+
+ // bottom row
+ te[ 12 ] = 0;
+ te[ 13 ] = 0;
+ te[ 14 ] = 0;
+ te[ 15 ] = 1;
+
+ return this;
+
+ },
+
+ lookAt: function () {
+
+ var x = new Vector3();
+ var y = new Vector3();
+ var z = new Vector3();
+
+ return function lookAt( eye, target, up ) {
+
+ var te = this.elements;
+
+ z.subVectors( eye, target );
+
+ if ( z.lengthSq() === 0 ) {
+
+ // eye and target are in the same position
+
+ z.z = 1;
+
+ }
+
+ z.normalize();
+ x.crossVectors( up, z );
+
+ if ( x.lengthSq() === 0 ) {
+
+ // up and z are parallel
+
+ if ( Math.abs( up.z ) === 1 ) {
+
+ z.x += 0.0001;
+
+ } else {
+
+ z.z += 0.0001;
+
+ }
+
+ z.normalize();
+ x.crossVectors( up, z );
+
+ }
+
+ x.normalize();
+ y.crossVectors( z, x );
+
+ te[ 0 ] = x.x; te[ 4 ] = y.x; te[ 8 ] = z.x;
+ te[ 1 ] = x.y; te[ 5 ] = y.y; te[ 9 ] = z.y;
+ te[ 2 ] = x.z; te[ 6 ] = y.z; te[ 10 ] = z.z;
+
+ return this;
+
+ };
+
+ }(),
+
+ multiply: function ( m, n ) {
+
+ if ( n !== undefined ) {
+
+ console.warn( 'THREE.Matrix4: .multiply() now only accepts one argument. Use .multiplyMatrices( a, b ) instead.' );
+ return this.multiplyMatrices( m, n );
+
+ }
+
+ return this.multiplyMatrices( this, m );
+
+ },
+
+ premultiply: function ( m ) {
+
+ return this.multiplyMatrices( m, this );
+
+ },
+
+ multiplyMatrices: function ( a, b ) {
+
+ var ae = a.elements;
+ var be = b.elements;
+ var te = this.elements;
+
+ var a11 = ae[ 0 ], a12 = ae[ 4 ], a13 = ae[ 8 ], a14 = ae[ 12 ];
+ var a21 = ae[ 1 ], a22 = ae[ 5 ], a23 = ae[ 9 ], a24 = ae[ 13 ];
+ var a31 = ae[ 2 ], a32 = ae[ 6 ], a33 = ae[ 10 ], a34 = ae[ 14 ];
+ var a41 = ae[ 3 ], a42 = ae[ 7 ], a43 = ae[ 11 ], a44 = ae[ 15 ];
+
+ var b11 = be[ 0 ], b12 = be[ 4 ], b13 = be[ 8 ], b14 = be[ 12 ];
+ var b21 = be[ 1 ], b22 = be[ 5 ], b23 = be[ 9 ], b24 = be[ 13 ];
+ var b31 = be[ 2 ], b32 = be[ 6 ], b33 = be[ 10 ], b34 = be[ 14 ];
+ var b41 = be[ 3 ], b42 = be[ 7 ], b43 = be[ 11 ], b44 = be[ 15 ];
+
+ te[ 0 ] = a11 * b11 + a12 * b21 + a13 * b31 + a14 * b41;
+ te[ 4 ] = a11 * b12 + a12 * b22 + a13 * b32 + a14 * b42;
+ te[ 8 ] = a11 * b13 + a12 * b23 + a13 * b33 + a14 * b43;
+ te[ 12 ] = a11 * b14 + a12 * b24 + a13 * b34 + a14 * b44;
+
+ te[ 1 ] = a21 * b11 + a22 * b21 + a23 * b31 + a24 * b41;
+ te[ 5 ] = a21 * b12 + a22 * b22 + a23 * b32 + a24 * b42;
+ te[ 9 ] = a21 * b13 + a22 * b23 + a23 * b33 + a24 * b43;
+ te[ 13 ] = a21 * b14 + a22 * b24 + a23 * b34 + a24 * b44;
+
+ te[ 2 ] = a31 * b11 + a32 * b21 + a33 * b31 + a34 * b41;
+ te[ 6 ] = a31 * b12 + a32 * b22 + a33 * b32 + a34 * b42;
+ te[ 10 ] = a31 * b13 + a32 * b23 + a33 * b33 + a34 * b43;
+ te[ 14 ] = a31 * b14 + a32 * b24 + a33 * b34 + a34 * b44;
+
+ te[ 3 ] = a41 * b11 + a42 * b21 + a43 * b31 + a44 * b41;
+ te[ 7 ] = a41 * b12 + a42 * b22 + a43 * b32 + a44 * b42;
+ te[ 11 ] = a41 * b13 + a42 * b23 + a43 * b33 + a44 * b43;
+ te[ 15 ] = a41 * b14 + a42 * b24 + a43 * b34 + a44 * b44;
+
+ return this;
+
+ },
+
+ multiplyScalar: function ( s ) {
+
+ var te = this.elements;
+
+ te[ 0 ] *= s; te[ 4 ] *= s; te[ 8 ] *= s; te[ 12 ] *= s;
+ te[ 1 ] *= s; te[ 5 ] *= s; te[ 9 ] *= s; te[ 13 ] *= s;
+ te[ 2 ] *= s; te[ 6 ] *= s; te[ 10 ] *= s; te[ 14 ] *= s;
+ te[ 3 ] *= s; te[ 7 ] *= s; te[ 11 ] *= s; te[ 15 ] *= s;
+
+ return this;
+
+ },
+
+ applyToBufferAttribute: function () {
+
+ var v1 = new Vector3();
+
+ return function applyToBufferAttribute( attribute ) {
+
+ for ( var i = 0, l = attribute.count; i < l; i ++ ) {
+
+ v1.x = attribute.getX( i );
+ v1.y = attribute.getY( i );
+ v1.z = attribute.getZ( i );
+
+ v1.applyMatrix4( this );
+
+ attribute.setXYZ( i, v1.x, v1.y, v1.z );
+
+ }
+
+ return attribute;
+
+ };
+
+ }(),
+
+ determinant: function () {
+
+ var te = this.elements;
+
+ var n11 = te[ 0 ], n12 = te[ 4 ], n13 = te[ 8 ], n14 = te[ 12 ];
+ var n21 = te[ 1 ], n22 = te[ 5 ], n23 = te[ 9 ], n24 = te[ 13 ];
+ var n31 = te[ 2 ], n32 = te[ 6 ], n33 = te[ 10 ], n34 = te[ 14 ];
+ var n41 = te[ 3 ], n42 = te[ 7 ], n43 = te[ 11 ], n44 = te[ 15 ];
+
+ //TODO: make this more efficient
+ //( based on http://www.euclideanspace.com/maths/algebra/matrix/functions/inverse/fourD/index.htm )
+
+ return (
+ n41 * (
+ + n14 * n23 * n32
+ - n13 * n24 * n32
+ - n14 * n22 * n33
+ + n12 * n24 * n33
+ + n13 * n22 * n34
+ - n12 * n23 * n34
+ ) +
+ n42 * (
+ + n11 * n23 * n34
+ - n11 * n24 * n33
+ + n14 * n21 * n33
+ - n13 * n21 * n34
+ + n13 * n24 * n31
+ - n14 * n23 * n31
+ ) +
+ n43 * (
+ + n11 * n24 * n32
+ - n11 * n22 * n34
+ - n14 * n21 * n32
+ + n12 * n21 * n34
+ + n14 * n22 * n31
+ - n12 * n24 * n31
+ ) +
+ n44 * (
+ - n13 * n22 * n31
+ - n11 * n23 * n32
+ + n11 * n22 * n33
+ + n13 * n21 * n32
+ - n12 * n21 * n33
+ + n12 * n23 * n31
+ )
+
+ );
+
+ },
+
+ transpose: function () {
+
+ var te = this.elements;
+ var tmp;
+
+ tmp = te[ 1 ]; te[ 1 ] = te[ 4 ]; te[ 4 ] = tmp;
+ tmp = te[ 2 ]; te[ 2 ] = te[ 8 ]; te[ 8 ] = tmp;
+ tmp = te[ 6 ]; te[ 6 ] = te[ 9 ]; te[ 9 ] = tmp;
+
+ tmp = te[ 3 ]; te[ 3 ] = te[ 12 ]; te[ 12 ] = tmp;
+ tmp = te[ 7 ]; te[ 7 ] = te[ 13 ]; te[ 13 ] = tmp;
+ tmp = te[ 11 ]; te[ 11 ] = te[ 14 ]; te[ 14 ] = tmp;
+
+ return this;
+
+ },
+
+ setPosition: function ( v ) {
+
+ var te = this.elements;
+
+ te[ 12 ] = v.x;
+ te[ 13 ] = v.y;
+ te[ 14 ] = v.z;
+
+ return this;
+
+ },
+
+ getInverse: function ( m, throwOnDegenerate ) {
+
+ // based on http://www.euclideanspace.com/maths/algebra/matrix/functions/inverse/fourD/index.htm
+ var te = this.elements,
+ me = m.elements,
+
+ n11 = me[ 0 ], n21 = me[ 1 ], n31 = me[ 2 ], n41 = me[ 3 ],
+ n12 = me[ 4 ], n22 = me[ 5 ], n32 = me[ 6 ], n42 = me[ 7 ],
+ n13 = me[ 8 ], n23 = me[ 9 ], n33 = me[ 10 ], n43 = me[ 11 ],
+ n14 = me[ 12 ], n24 = me[ 13 ], n34 = me[ 14 ], n44 = me[ 15 ],
+
+ t11 = n23 * n34 * n42 - n24 * n33 * n42 + n24 * n32 * n43 - n22 * n34 * n43 - n23 * n32 * n44 + n22 * n33 * n44,
+ t12 = n14 * n33 * n42 - n13 * n34 * n42 - n14 * n32 * n43 + n12 * n34 * n43 + n13 * n32 * n44 - n12 * n33 * n44,
+ t13 = n13 * n24 * n42 - n14 * n23 * n42 + n14 * n22 * n43 - n12 * n24 * n43 - n13 * n22 * n44 + n12 * n23 * n44,
+ t14 = n14 * n23 * n32 - n13 * n24 * n32 - n14 * n22 * n33 + n12 * n24 * n33 + n13 * n22 * n34 - n12 * n23 * n34;
+
+ var det = n11 * t11 + n21 * t12 + n31 * t13 + n41 * t14;
+
+ if ( det === 0 ) {
+
+ var msg = "THREE.Matrix4: .getInverse() can't invert matrix, determinant is 0";
+
+ if ( throwOnDegenerate === true ) {
+
+ throw new Error( msg );
+
+ } else {
+
+ console.warn( msg );
+
+ }
+
+ return this.identity();
+
+ }
+
+ var detInv = 1 / det;
+
+ te[ 0 ] = t11 * detInv;
+ te[ 1 ] = ( n24 * n33 * n41 - n23 * n34 * n41 - n24 * n31 * n43 + n21 * n34 * n43 + n23 * n31 * n44 - n21 * n33 * n44 ) * detInv;
+ te[ 2 ] = ( n22 * n34 * n41 - n24 * n32 * n41 + n24 * n31 * n42 - n21 * n34 * n42 - n22 * n31 * n44 + n21 * n32 * n44 ) * detInv;
+ te[ 3 ] = ( n23 * n32 * n41 - n22 * n33 * n41 - n23 * n31 * n42 + n21 * n33 * n42 + n22 * n31 * n43 - n21 * n32 * n43 ) * detInv;
+
+ te[ 4 ] = t12 * detInv;
+ te[ 5 ] = ( n13 * n34 * n41 - n14 * n33 * n41 + n14 * n31 * n43 - n11 * n34 * n43 - n13 * n31 * n44 + n11 * n33 * n44 ) * detInv;
+ te[ 6 ] = ( n14 * n32 * n41 - n12 * n34 * n41 - n14 * n31 * n42 + n11 * n34 * n42 + n12 * n31 * n44 - n11 * n32 * n44 ) * detInv;
+ te[ 7 ] = ( n12 * n33 * n41 - n13 * n32 * n41 + n13 * n31 * n42 - n11 * n33 * n42 - n12 * n31 * n43 + n11 * n32 * n43 ) * detInv;
+
+ te[ 8 ] = t13 * detInv;
+ te[ 9 ] = ( n14 * n23 * n41 - n13 * n24 * n41 - n14 * n21 * n43 + n11 * n24 * n43 + n13 * n21 * n44 - n11 * n23 * n44 ) * detInv;
+ te[ 10 ] = ( n12 * n24 * n41 - n14 * n22 * n41 + n14 * n21 * n42 - n11 * n24 * n42 - n12 * n21 * n44 + n11 * n22 * n44 ) * detInv;
+ te[ 11 ] = ( n13 * n22 * n41 - n12 * n23 * n41 - n13 * n21 * n42 + n11 * n23 * n42 + n12 * n21 * n43 - n11 * n22 * n43 ) * detInv;
+
+ te[ 12 ] = t14 * detInv;
+ te[ 13 ] = ( n13 * n24 * n31 - n14 * n23 * n31 + n14 * n21 * n33 - n11 * n24 * n33 - n13 * n21 * n34 + n11 * n23 * n34 ) * detInv;
+ te[ 14 ] = ( n14 * n22 * n31 - n12 * n24 * n31 - n14 * n21 * n32 + n11 * n24 * n32 + n12 * n21 * n34 - n11 * n22 * n34 ) * detInv;
+ te[ 15 ] = ( n12 * n23 * n31 - n13 * n22 * n31 + n13 * n21 * n32 - n11 * n23 * n32 - n12 * n21 * n33 + n11 * n22 * n33 ) * detInv;
+
+ return this;
+
+ },
+
+ scale: function ( v ) {
+
+ var te = this.elements;
+ var x = v.x, y = v.y, z = v.z;
+
+ te[ 0 ] *= x; te[ 4 ] *= y; te[ 8 ] *= z;
+ te[ 1 ] *= x; te[ 5 ] *= y; te[ 9 ] *= z;
+ te[ 2 ] *= x; te[ 6 ] *= y; te[ 10 ] *= z;
+ te[ 3 ] *= x; te[ 7 ] *= y; te[ 11 ] *= z;
+
+ return this;
+
+ },
+
+ getMaxScaleOnAxis: function () {
+
+ var te = this.elements;
+
+ var scaleXSq = te[ 0 ] * te[ 0 ] + te[ 1 ] * te[ 1 ] + te[ 2 ] * te[ 2 ];
+ var scaleYSq = te[ 4 ] * te[ 4 ] + te[ 5 ] * te[ 5 ] + te[ 6 ] * te[ 6 ];
+ var scaleZSq = te[ 8 ] * te[ 8 ] + te[ 9 ] * te[ 9 ] + te[ 10 ] * te[ 10 ];
+
+ return Math.sqrt( Math.max( scaleXSq, scaleYSq, scaleZSq ) );
+
+ },
+
+ makeTranslation: function ( x, y, z ) {
+
+ this.set(
+
+ 1, 0, 0, x,
+ 0, 1, 0, y,
+ 0, 0, 1, z,
+ 0, 0, 0, 1
+
+ );
+
+ return this;
+
+ },
+
+ makeRotationX: function ( theta ) {
+
+ var c = Math.cos( theta ), s = Math.sin( theta );
+
+ this.set(
+
+ 1, 0, 0, 0,
+ 0, c, - s, 0,
+ 0, s, c, 0,
+ 0, 0, 0, 1
+
+ );
+
+ return this;
+
+ },
+
+ makeRotationY: function ( theta ) {
+
+ var c = Math.cos( theta ), s = Math.sin( theta );
+
+ this.set(
+
+ c, 0, s, 0,
+ 0, 1, 0, 0,
+ - s, 0, c, 0,
+ 0, 0, 0, 1
+
+ );
+
+ return this;
+
+ },
+
+ makeRotationZ: function ( theta ) {
+
+ var c = Math.cos( theta ), s = Math.sin( theta );
+
+ this.set(
+
+ c, - s, 0, 0,
+ s, c, 0, 0,
+ 0, 0, 1, 0,
+ 0, 0, 0, 1
+
+ );
+
+ return this;
+
+ },
+
+ makeRotationAxis: function ( axis, angle ) {
+
+ // Based on http://www.gamedev.net/reference/articles/article1199.asp
+
+ var c = Math.cos( angle );
+ var s = Math.sin( angle );
+ var t = 1 - c;
+ var x = axis.x, y = axis.y, z = axis.z;
+ var tx = t * x, ty = t * y;
+
+ this.set(
+
+ tx * x + c, tx * y - s * z, tx * z + s * y, 0,
+ tx * y + s * z, ty * y + c, ty * z - s * x, 0,
+ tx * z - s * y, ty * z + s * x, t * z * z + c, 0,
+ 0, 0, 0, 1
+
+ );
+
+ return this;
+
+ },
+
+ makeScale: function ( x, y, z ) {
+
+ this.set(
+
+ x, 0, 0, 0,
+ 0, y, 0, 0,
+ 0, 0, z, 0,
+ 0, 0, 0, 1
+
+ );
+
+ return this;
+
+ },
+
+ makeShear: function ( x, y, z ) {
+
+ this.set(
+
+ 1, y, z, 0,
+ x, 1, z, 0,
+ x, y, 1, 0,
+ 0, 0, 0, 1
+
+ );
+
+ return this;
+
+ },
+
+ compose: function ( position, quaternion, scale ) {
+
+ this.makeRotationFromQuaternion( quaternion );
+ this.scale( scale );
+ this.setPosition( position );
+
+ return this;
+
+ },
+
+ decompose: function () {
+
+ var vector = new Vector3();
+ var matrix = new Matrix4();
+
+ return function decompose( position, quaternion, scale ) {
+
+ var te = this.elements;
+
+ var sx = vector.set( te[ 0 ], te[ 1 ], te[ 2 ] ).length();
+ var sy = vector.set( te[ 4 ], te[ 5 ], te[ 6 ] ).length();
+ var sz = vector.set( te[ 8 ], te[ 9 ], te[ 10 ] ).length();
+
+ // if determine is negative, we need to invert one scale
+ var det = this.determinant();
+ if ( det < 0 ) sx = - sx;
+
+ position.x = te[ 12 ];
+ position.y = te[ 13 ];
+ position.z = te[ 14 ];
+
+ // scale the rotation part
+ matrix.copy( this );
+
+ var invSX = 1 / sx;
+ var invSY = 1 / sy;
+ var invSZ = 1 / sz;
+
+ matrix.elements[ 0 ] *= invSX;
+ matrix.elements[ 1 ] *= invSX;
+ matrix.elements[ 2 ] *= invSX;
+
+ matrix.elements[ 4 ] *= invSY;
+ matrix.elements[ 5 ] *= invSY;
+ matrix.elements[ 6 ] *= invSY;
+
+ matrix.elements[ 8 ] *= invSZ;
+ matrix.elements[ 9 ] *= invSZ;
+ matrix.elements[ 10 ] *= invSZ;
+
+ quaternion.setFromRotationMatrix( matrix );
+
+ scale.x = sx;
+ scale.y = sy;
+ scale.z = sz;
+
+ return this;
+
+ };
+
+ }(),
+
+ makePerspective: function ( left, right, top, bottom, near, far ) {
+
+ if ( far === undefined ) {
+
+ console.warn( 'THREE.Matrix4: .makePerspective() has been redefined and has a new signature. Please check the docs.' );
+
+ }
+
+ var te = this.elements;
+ var x = 2 * near / ( right - left );
+ var y = 2 * near / ( top - bottom );
+
+ var a = ( right + left ) / ( right - left );
+ var b = ( top + bottom ) / ( top - bottom );
+ var c = - ( far + near ) / ( far - near );
+ var d = - 2 * far * near / ( far - near );
+
+ te[ 0 ] = x; te[ 4 ] = 0; te[ 8 ] = a; te[ 12 ] = 0;
+ te[ 1 ] = 0; te[ 5 ] = y; te[ 9 ] = b; te[ 13 ] = 0;
+ te[ 2 ] = 0; te[ 6 ] = 0; te[ 10 ] = c; te[ 14 ] = d;
+ te[ 3 ] = 0; te[ 7 ] = 0; te[ 11 ] = - 1; te[ 15 ] = 0;
+
+ return this;
+
+ },
+
+ makeOrthographic: function ( left, right, top, bottom, near, far ) {
+
+ var te = this.elements;
+ var w = 1.0 / ( right - left );
+ var h = 1.0 / ( top - bottom );
+ var p = 1.0 / ( far - near );
+
+ var x = ( right + left ) * w;
+ var y = ( top + bottom ) * h;
+ var z = ( far + near ) * p;
+
+ te[ 0 ] = 2 * w; te[ 4 ] = 0; te[ 8 ] = 0; te[ 12 ] = - x;
+ te[ 1 ] = 0; te[ 5 ] = 2 * h; te[ 9 ] = 0; te[ 13 ] = - y;
+ te[ 2 ] = 0; te[ 6 ] = 0; te[ 10 ] = - 2 * p; te[ 14 ] = - z;
+ te[ 3 ] = 0; te[ 7 ] = 0; te[ 11 ] = 0; te[ 15 ] = 1;
+
+ return this;
+
+ },
+
+ equals: function ( matrix ) {
+
+ var te = this.elements;
+ var me = matrix.elements;
+
+ for ( var i = 0; i < 16; i ++ ) {
+
+ if ( te[ i ] !== me[ i ] ) return false;
+
+ }
+
+ return true;
+
+ },
+
+ fromArray: function ( array, offset ) {
+
+ if ( offset === undefined ) offset = 0;
+
+ for ( var i = 0; i < 16; i ++ ) {
+
+ this.elements[ i ] = array[ i + offset ];
+
+ }
+
+ return this;
+
+ },
+
+ toArray: function ( array, offset ) {
+
+ if ( array === undefined ) array = [];
+ if ( offset === undefined ) offset = 0;
+
+ var te = this.elements;
+
+ array[ offset ] = te[ 0 ];
+ array[ offset + 1 ] = te[ 1 ];
+ array[ offset + 2 ] = te[ 2 ];
+ array[ offset + 3 ] = te[ 3 ];
+
+ array[ offset + 4 ] = te[ 4 ];
+ array[ offset + 5 ] = te[ 5 ];
+ array[ offset + 6 ] = te[ 6 ];
+ array[ offset + 7 ] = te[ 7 ];
+
+ array[ offset + 8 ] = te[ 8 ];
+ array[ offset + 9 ] = te[ 9 ];
+ array[ offset + 10 ] = te[ 10 ];
+ array[ offset + 11 ] = te[ 11 ];
+
+ array[ offset + 12 ] = te[ 12 ];
+ array[ offset + 13 ] = te[ 13 ];
+ array[ offset + 14 ] = te[ 14 ];
+ array[ offset + 15 ] = te[ 15 ];
+
+ return array;
+
+ }
+
+} );
+
+/**
+ * @author mikael emtinger / http://gomo.se/
+ * @author alteredq / http://alteredqualia.com/
+ * @author WestLangley / http://github.com/WestLangley
+ * @author bhouston / http://clara.io
+ */
+
+function Quaternion( x, y, z, w ) {
+
+ this._x = x || 0;
+ this._y = y || 0;
+ this._z = z || 0;
+ this._w = ( w !== undefined ) ? w : 1;
+
+}
+
+Object.assign( Quaternion, {
+
+ slerp: function ( qa, qb, qm, t ) {
+
+ return qm.copy( qa ).slerp( qb, t );
+
+ },
+
+ slerpFlat: function ( dst, dstOffset, src0, srcOffset0, src1, srcOffset1, t ) {
+
+ // fuzz-free, array-based Quaternion SLERP operation
+
+ var x0 = src0[ srcOffset0 + 0 ],
+ y0 = src0[ srcOffset0 + 1 ],
+ z0 = src0[ srcOffset0 + 2 ],
+ w0 = src0[ srcOffset0 + 3 ],
+
+ x1 = src1[ srcOffset1 + 0 ],
+ y1 = src1[ srcOffset1 + 1 ],
+ z1 = src1[ srcOffset1 + 2 ],
+ w1 = src1[ srcOffset1 + 3 ];
+
+ if ( w0 !== w1 || x0 !== x1 || y0 !== y1 || z0 !== z1 ) {
+
+ var s = 1 - t,
+
+ cos = x0 * x1 + y0 * y1 + z0 * z1 + w0 * w1,
+
+ dir = ( cos >= 0 ? 1 : - 1 ),
+ sqrSin = 1 - cos * cos;
+
+ // Skip the Slerp for tiny steps to avoid numeric problems:
+ if ( sqrSin > Number.EPSILON ) {
+
+ var sin = Math.sqrt( sqrSin ),
+ len = Math.atan2( sin, cos * dir );
+
+ s = Math.sin( s * len ) / sin;
+ t = Math.sin( t * len ) / sin;
+
+ }
+
+ var tDir = t * dir;
+
+ x0 = x0 * s + x1 * tDir;
+ y0 = y0 * s + y1 * tDir;
+ z0 = z0 * s + z1 * tDir;
+ w0 = w0 * s + w1 * tDir;
+
+ // Normalize in case we just did a lerp:
+ if ( s === 1 - t ) {
+
+ var f = 1 / Math.sqrt( x0 * x0 + y0 * y0 + z0 * z0 + w0 * w0 );
+
+ x0 *= f;
+ y0 *= f;
+ z0 *= f;
+ w0 *= f;
+
+ }
+
+ }
+
+ dst[ dstOffset ] = x0;
+ dst[ dstOffset + 1 ] = y0;
+ dst[ dstOffset + 2 ] = z0;
+ dst[ dstOffset + 3 ] = w0;
+
+ }
+
+} );
+
+Object.defineProperties( Quaternion.prototype, {
+
+ x: {
+
+ get: function () {
+
+ return this._x;
+
+ },
+
+ set: function ( value ) {
+
+ this._x = value;
+ this.onChangeCallback();
+
+ }
+
+ },
+
+ y: {
+
+ get: function () {
+
+ return this._y;
+
+ },
+
+ set: function ( value ) {
+
+ this._y = value;
+ this.onChangeCallback();
+
+ }
+
+ },
+
+ z: {
+
+ get: function () {
+
+ return this._z;
+
+ },
+
+ set: function ( value ) {
+
+ this._z = value;
+ this.onChangeCallback();
+
+ }
+
+ },
+
+ w: {
+
+ get: function () {
+
+ return this._w;
+
+ },
+
+ set: function ( value ) {
+
+ this._w = value;
+ this.onChangeCallback();
+
+ }
+
+ }
+
+} );
+
+Object.assign( Quaternion.prototype, {
+
+ set: function ( x, y, z, w ) {
+
+ this._x = x;
+ this._y = y;
+ this._z = z;
+ this._w = w;
+
+ this.onChangeCallback();
+
+ return this;
+
+ },
+
+ clone: function () {
+
+ return new this.constructor( this._x, this._y, this._z, this._w );
+
+ },
+
+ copy: function ( quaternion ) {
+
+ this._x = quaternion.x;
+ this._y = quaternion.y;
+ this._z = quaternion.z;
+ this._w = quaternion.w;
+
+ this.onChangeCallback();
+
+ return this;
+
+ },
+
+ setFromEuler: function ( euler, update ) {
+
+ if ( ! ( euler && euler.isEuler ) ) {
+
+ throw new Error( 'THREE.Quaternion: .setFromEuler() now expects an Euler rotation rather than a Vector3 and order.' );
+
+ }
+
+ var x = euler._x, y = euler._y, z = euler._z, order = euler.order;
+
+ // http://www.mathworks.com/matlabcentral/fileexchange/
+ // 20696-function-to-convert-between-dcm-euler-angles-quaternions-and-euler-vectors/
+ // content/SpinCalc.m
+
+ var cos = Math.cos;
+ var sin = Math.sin;
+
+ var c1 = cos( x / 2 );
+ var c2 = cos( y / 2 );
+ var c3 = cos( z / 2 );
+
+ var s1 = sin( x / 2 );
+ var s2 = sin( y / 2 );
+ var s3 = sin( z / 2 );
+
+ if ( order === 'XYZ' ) {
+
+ this._x = s1 * c2 * c3 + c1 * s2 * s3;
+ this._y = c1 * s2 * c3 - s1 * c2 * s3;
+ this._z = c1 * c2 * s3 + s1 * s2 * c3;
+ this._w = c1 * c2 * c3 - s1 * s2 * s3;
+
+ } else if ( order === 'YXZ' ) {
+
+ this._x = s1 * c2 * c3 + c1 * s2 * s3;
+ this._y = c1 * s2 * c3 - s1 * c2 * s3;
+ this._z = c1 * c2 * s3 - s1 * s2 * c3;
+ this._w = c1 * c2 * c3 + s1 * s2 * s3;
+
+ } else if ( order === 'ZXY' ) {
+
+ this._x = s1 * c2 * c3 - c1 * s2 * s3;
+ this._y = c1 * s2 * c3 + s1 * c2 * s3;
+ this._z = c1 * c2 * s3 + s1 * s2 * c3;
+ this._w = c1 * c2 * c3 - s1 * s2 * s3;
+
+ } else if ( order === 'ZYX' ) {
+
+ this._x = s1 * c2 * c3 - c1 * s2 * s3;
+ this._y = c1 * s2 * c3 + s1 * c2 * s3;
+ this._z = c1 * c2 * s3 - s1 * s2 * c3;
+ this._w = c1 * c2 * c3 + s1 * s2 * s3;
+
+ } else if ( order === 'YZX' ) {
+
+ this._x = s1 * c2 * c3 + c1 * s2 * s3;
+ this._y = c1 * s2 * c3 + s1 * c2 * s3;
+ this._z = c1 * c2 * s3 - s1 * s2 * c3;
+ this._w = c1 * c2 * c3 - s1 * s2 * s3;
+
+ } else if ( order === 'XZY' ) {
+
+ this._x = s1 * c2 * c3 - c1 * s2 * s3;
+ this._y = c1 * s2 * c3 - s1 * c2 * s3;
+ this._z = c1 * c2 * s3 + s1 * s2 * c3;
+ this._w = c1 * c2 * c3 + s1 * s2 * s3;
+
+ }
+
+ if ( update !== false ) this.onChangeCallback();
+
+ return this;
+
+ },
+
+ setFromAxisAngle: function ( axis, angle ) {
+
+ // http://www.euclideanspace.com/maths/geometry/rotations/conversions/angleToQuaternion/index.htm
+
+ // assumes axis is normalized
+
+ var halfAngle = angle / 2, s = Math.sin( halfAngle );
+
+ this._x = axis.x * s;
+ this._y = axis.y * s;
+ this._z = axis.z * s;
+ this._w = Math.cos( halfAngle );
+
+ this.onChangeCallback();
+
+ return this;
+
+ },
+
+ setFromRotationMatrix: function ( m ) {
+
+ // http://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToQuaternion/index.htm
+
+ // assumes the upper 3x3 of m is a pure rotation matrix (i.e, unscaled)
+
+ var te = m.elements,
+
+ m11 = te[ 0 ], m12 = te[ 4 ], m13 = te[ 8 ],
+ m21 = te[ 1 ], m22 = te[ 5 ], m23 = te[ 9 ],
+ m31 = te[ 2 ], m32 = te[ 6 ], m33 = te[ 10 ],
+
+ trace = m11 + m22 + m33,
+ s;
+
+ if ( trace > 0 ) {
+
+ s = 0.5 / Math.sqrt( trace + 1.0 );
+
+ this._w = 0.25 / s;
+ this._x = ( m32 - m23 ) * s;
+ this._y = ( m13 - m31 ) * s;
+ this._z = ( m21 - m12 ) * s;
+
+ } else if ( m11 > m22 && m11 > m33 ) {
+
+ s = 2.0 * Math.sqrt( 1.0 + m11 - m22 - m33 );
+
+ this._w = ( m32 - m23 ) / s;
+ this._x = 0.25 * s;
+ this._y = ( m12 + m21 ) / s;
+ this._z = ( m13 + m31 ) / s;
+
+ } else if ( m22 > m33 ) {
+
+ s = 2.0 * Math.sqrt( 1.0 + m22 - m11 - m33 );
+
+ this._w = ( m13 - m31 ) / s;
+ this._x = ( m12 + m21 ) / s;
+ this._y = 0.25 * s;
+ this._z = ( m23 + m32 ) / s;
+
+ } else {
+
+ s = 2.0 * Math.sqrt( 1.0 + m33 - m11 - m22 );
+
+ this._w = ( m21 - m12 ) / s;
+ this._x = ( m13 + m31 ) / s;
+ this._y = ( m23 + m32 ) / s;
+ this._z = 0.25 * s;
+
+ }
+
+ this.onChangeCallback();
+
+ return this;
+
+ },
+
+ setFromUnitVectors: function () {
+
+ // assumes direction vectors vFrom and vTo are normalized
+
+ var v1 = new Vector3();
+ var r;
+
+ var EPS = 0.000001;
+
+ return function setFromUnitVectors( vFrom, vTo ) {
+
+ if ( v1 === undefined ) v1 = new Vector3();
+
+ r = vFrom.dot( vTo ) + 1;
+
+ if ( r < EPS ) {
+
+ r = 0;
+
+ if ( Math.abs( vFrom.x ) > Math.abs( vFrom.z ) ) {
+
+ v1.set( - vFrom.y, vFrom.x, 0 );
+
+ } else {
+
+ v1.set( 0, - vFrom.z, vFrom.y );
+
+ }
+
+ } else {
+
+ v1.crossVectors( vFrom, vTo );
+
+ }
+
+ this._x = v1.x;
+ this._y = v1.y;
+ this._z = v1.z;
+ this._w = r;
+
+ return this.normalize();
+
+ };
+
+ }(),
+
+ inverse: function () {
+
+ return this.conjugate().normalize();
+
+ },
+
+ conjugate: function () {
+
+ this._x *= - 1;
+ this._y *= - 1;
+ this._z *= - 1;
+
+ this.onChangeCallback();
+
+ return this;
+
+ },
+
+ dot: function ( v ) {
+
+ return this._x * v._x + this._y * v._y + this._z * v._z + this._w * v._w;
+
+ },
+
+ lengthSq: function () {
+
+ return this._x * this._x + this._y * this._y + this._z * this._z + this._w * this._w;
+
+ },
+
+ length: function () {
+
+ return Math.sqrt( this._x * this._x + this._y * this._y + this._z * this._z + this._w * this._w );
+
+ },
+
+ normalize: function () {
+
+ var l = this.length();
+
+ if ( l === 0 ) {
+
+ this._x = 0;
+ this._y = 0;
+ this._z = 0;
+ this._w = 1;
+
+ } else {
+
+ l = 1 / l;
+
+ this._x = this._x * l;
+ this._y = this._y * l;
+ this._z = this._z * l;
+ this._w = this._w * l;
+
+ }
+
+ this.onChangeCallback();
+
+ return this;
+
+ },
+
+ multiply: function ( q, p ) {
+
+ if ( p !== undefined ) {
+
+ console.warn( 'THREE.Quaternion: .multiply() now only accepts one argument. Use .multiplyQuaternions( a, b ) instead.' );
+ return this.multiplyQuaternions( q, p );
+
+ }
+
+ return this.multiplyQuaternions( this, q );
+
+ },
+
+ premultiply: function ( q ) {
+
+ return this.multiplyQuaternions( q, this );
+
+ },
+
+ multiplyQuaternions: function ( a, b ) {
+
+ // from http://www.euclideanspace.com/maths/algebra/realNormedAlgebra/quaternions/code/index.htm
+
+ var qax = a._x, qay = a._y, qaz = a._z, qaw = a._w;
+ var qbx = b._x, qby = b._y, qbz = b._z, qbw = b._w;
+
+ this._x = qax * qbw + qaw * qbx + qay * qbz - qaz * qby;
+ this._y = qay * qbw + qaw * qby + qaz * qbx - qax * qbz;
+ this._z = qaz * qbw + qaw * qbz + qax * qby - qay * qbx;
+ this._w = qaw * qbw - qax * qbx - qay * qby - qaz * qbz;
+
+ this.onChangeCallback();
+
+ return this;
+
+ },
+
+ slerp: function ( qb, t ) {
+
+ if ( t === 0 ) return this;
+ if ( t === 1 ) return this.copy( qb );
+
+ var x = this._x, y = this._y, z = this._z, w = this._w;
+
+ // http://www.euclideanspace.com/maths/algebra/realNormedAlgebra/quaternions/slerp/
+
+ var cosHalfTheta = w * qb._w + x * qb._x + y * qb._y + z * qb._z;
+
+ if ( cosHalfTheta < 0 ) {
+
+ this._w = - qb._w;
+ this._x = - qb._x;
+ this._y = - qb._y;
+ this._z = - qb._z;
+
+ cosHalfTheta = - cosHalfTheta;
+
+ } else {
+
+ this.copy( qb );
+
+ }
+
+ if ( cosHalfTheta >= 1.0 ) {
+
+ this._w = w;
+ this._x = x;
+ this._y = y;
+ this._z = z;
+
+ return this;
+
+ }
+
+ var sinHalfTheta = Math.sqrt( 1.0 - cosHalfTheta * cosHalfTheta );
+
+ if ( Math.abs( sinHalfTheta ) < 0.001 ) {
+
+ this._w = 0.5 * ( w + this._w );
+ this._x = 0.5 * ( x + this._x );
+ this._y = 0.5 * ( y + this._y );
+ this._z = 0.5 * ( z + this._z );
+
+ return this;
+
+ }
+
+ var halfTheta = Math.atan2( sinHalfTheta, cosHalfTheta );
+ var ratioA = Math.sin( ( 1 - t ) * halfTheta ) / sinHalfTheta,
+ ratioB = Math.sin( t * halfTheta ) / sinHalfTheta;
+
+ this._w = ( w * ratioA + this._w * ratioB );
+ this._x = ( x * ratioA + this._x * ratioB );
+ this._y = ( y * ratioA + this._y * ratioB );
+ this._z = ( z * ratioA + this._z * ratioB );
+
+ this.onChangeCallback();
+
+ return this;
+
+ },
+
+ equals: function ( quaternion ) {
+
+ return ( quaternion._x === this._x ) && ( quaternion._y === this._y ) && ( quaternion._z === this._z ) && ( quaternion._w === this._w );
+
+ },
+
+ fromArray: function ( array, offset ) {
+
+ if ( offset === undefined ) offset = 0;
+
+ this._x = array[ offset ];
+ this._y = array[ offset + 1 ];
+ this._z = array[ offset + 2 ];
+ this._w = array[ offset + 3 ];
+
+ this.onChangeCallback();
+
+ return this;
+
+ },
+
+ toArray: function ( array, offset ) {
+
+ if ( array === undefined ) array = [];
+ if ( offset === undefined ) offset = 0;
+
+ array[ offset ] = this._x;
+ array[ offset + 1 ] = this._y;
+ array[ offset + 2 ] = this._z;
+ array[ offset + 3 ] = this._w;
+
+ return array;
+
+ },
+
+ onChange: function ( callback ) {
+
+ this.onChangeCallback = callback;
+
+ return this;
+
+ },
+
+ onChangeCallback: function () {}
+
+} );
+
+/**
+ * @author mrdoob / http://mrdoob.com/
+ * @author kile / http://kile.stravaganza.org/
+ * @author philogb / http://blog.thejit.org/
+ * @author mikael emtinger / http://gomo.se/
+ * @author egraether / http://egraether.com/
+ * @author WestLangley / http://github.com/WestLangley
+ */
+
+function Vector3( x, y, z ) {
+
+ this.x = x || 0;
+ this.y = y || 0;
+ this.z = z || 0;
+
+}
+
+Object.assign( Vector3.prototype, {
+
+ isVector3: true,
+
+ set: function ( x, y, z ) {
+
+ this.x = x;
+ this.y = y;
+ this.z = z;
+
+ return this;
+
+ },
+
+ setScalar: function ( scalar ) {
+
+ this.x = scalar;
+ this.y = scalar;
+ this.z = scalar;
+
+ return this;
+
+ },
+
+ setX: function ( x ) {
+
+ this.x = x;
+
+ return this;
+
+ },
+
+ setY: function ( y ) {
+
+ this.y = y;
+
+ return this;
+
+ },
+
+ setZ: function ( z ) {
+
+ this.z = z;
+
+ return this;
+
+ },
+
+ setComponent: function ( index, value ) {
+
+ switch ( index ) {
+
+ case 0: this.x = value; break;
+ case 1: this.y = value; break;
+ case 2: this.z = value; break;
+ default: throw new Error( 'index is out of range: ' + index );
+
+ }
+
+ return this;
+
+ },
+
+ getComponent: function ( index ) {
+
+ switch ( index ) {
+
+ case 0: return this.x;
+ case 1: return this.y;
+ case 2: return this.z;
+ default: throw new Error( 'index is out of range: ' + index );
+
+ }
+
+ },
+
+ clone: function () {
+
+ return new this.constructor( this.x, this.y, this.z );
+
+ },
+
+ copy: function ( v ) {
+
+ this.x = v.x;
+ this.y = v.y;
+ this.z = v.z;
+
+ return this;
+
+ },
+
+ add: function ( v, w ) {
+
+ if ( w !== undefined ) {
+
+ console.warn( 'THREE.Vector3: .add() now only accepts one argument. Use .addVectors( a, b ) instead.' );
+ return this.addVectors( v, w );
+
+ }
+
+ this.x += v.x;
+ this.y += v.y;
+ this.z += v.z;
+
+ return this;
+
+ },
+
+ addScalar: function ( s ) {
+
+ this.x += s;
+ this.y += s;
+ this.z += s;
+
+ return this;
+
+ },
+
+ addVectors: function ( a, b ) {
+
+ this.x = a.x + b.x;
+ this.y = a.y + b.y;
+ this.z = a.z + b.z;
+
+ return this;
+
+ },
+
+ addScaledVector: function ( v, s ) {
+
+ this.x += v.x * s;
+ this.y += v.y * s;
+ this.z += v.z * s;
+
+ return this;
+
+ },
+
+ sub: function ( v, w ) {
+
+ if ( w !== undefined ) {
+
+ console.warn( 'THREE.Vector3: .sub() now only accepts one argument. Use .subVectors( a, b ) instead.' );
+ return this.subVectors( v, w );
+
+ }
+
+ this.x -= v.x;
+ this.y -= v.y;
+ this.z -= v.z;
+
+ return this;
+
+ },
+
+ subScalar: function ( s ) {
+
+ this.x -= s;
+ this.y -= s;
+ this.z -= s;
+
+ return this;
+
+ },
+
+ subVectors: function ( a, b ) {
+
+ this.x = a.x - b.x;
+ this.y = a.y - b.y;
+ this.z = a.z - b.z;
+
+ return this;
+
+ },
+
+ multiply: function ( v, w ) {
+
+ if ( w !== undefined ) {
+
+ console.warn( 'THREE.Vector3: .multiply() now only accepts one argument. Use .multiplyVectors( a, b ) instead.' );
+ return this.multiplyVectors( v, w );
+
+ }
+
+ this.x *= v.x;
+ this.y *= v.y;
+ this.z *= v.z;
+
+ return this;
+
+ },
+
+ multiplyScalar: function ( scalar ) {
+
+ this.x *= scalar;
+ this.y *= scalar;
+ this.z *= scalar;
+
+ return this;
+
+ },
+
+ multiplyVectors: function ( a, b ) {
+
+ this.x = a.x * b.x;
+ this.y = a.y * b.y;
+ this.z = a.z * b.z;
+
+ return this;
+
+ },
+
+ applyEuler: function () {
+
+ var quaternion = new Quaternion();
+
+ return function applyEuler( euler ) {
+
+ if ( ! ( euler && euler.isEuler ) ) {
+
+ console.error( 'THREE.Vector3: .applyEuler() now expects an Euler rotation rather than a Vector3 and order.' );
+
+ }
+
+ return this.applyQuaternion( quaternion.setFromEuler( euler ) );
+
+ };
+
+ }(),
+
+ applyAxisAngle: function () {
+
+ var quaternion = new Quaternion();
+
+ return function applyAxisAngle( axis, angle ) {
+
+ return this.applyQuaternion( quaternion.setFromAxisAngle( axis, angle ) );
+
+ };
+
+ }(),
+
+ applyMatrix3: function ( m ) {
+
+ var x = this.x, y = this.y, z = this.z;
+ var e = m.elements;
+
+ this.x = e[ 0 ] * x + e[ 3 ] * y + e[ 6 ] * z;
+ this.y = e[ 1 ] * x + e[ 4 ] * y + e[ 7 ] * z;
+ this.z = e[ 2 ] * x + e[ 5 ] * y + e[ 8 ] * z;
+
+ return this;
+
+ },
+
+ applyMatrix4: function ( m ) {
+
+ var x = this.x, y = this.y, z = this.z;
+ var e = m.elements;
+
+ var w = 1 / ( e[ 3 ] * x + e[ 7 ] * y + e[ 11 ] * z + e[ 15 ] );
+
+ this.x = ( e[ 0 ] * x + e[ 4 ] * y + e[ 8 ] * z + e[ 12 ] ) * w;
+ this.y = ( e[ 1 ] * x + e[ 5 ] * y + e[ 9 ] * z + e[ 13 ] ) * w;
+ this.z = ( e[ 2 ] * x + e[ 6 ] * y + e[ 10 ] * z + e[ 14 ] ) * w;
+
+ return this;
+
+ },
+
+ applyQuaternion: function ( q ) {
+
+ var x = this.x, y = this.y, z = this.z;
+ var qx = q.x, qy = q.y, qz = q.z, qw = q.w;
+
+ // calculate quat * vector
+
+ var ix = qw * x + qy * z - qz * y;
+ var iy = qw * y + qz * x - qx * z;
+ var iz = qw * z + qx * y - qy * x;
+ var iw = - qx * x - qy * y - qz * z;
+
+ // calculate result * inverse quat
+
+ this.x = ix * qw + iw * - qx + iy * - qz - iz * - qy;
+ this.y = iy * qw + iw * - qy + iz * - qx - ix * - qz;
+ this.z = iz * qw + iw * - qz + ix * - qy - iy * - qx;
+
+ return this;
+
+ },
+
+ project: function () {
+
+ var matrix = new Matrix4();
+
+ return function project( camera ) {
+
+ matrix.multiplyMatrices( camera.projectionMatrix, matrix.getInverse( camera.matrixWorld ) );
+ return this.applyMatrix4( matrix );
+
+ };
+
+ }(),
+
+ unproject: function () {
+
+ var matrix = new Matrix4();
+
+ return function unproject( camera ) {
+
+ matrix.multiplyMatrices( camera.matrixWorld, matrix.getInverse( camera.projectionMatrix ) );
+ return this.applyMatrix4( matrix );
+
+ };
+
+ }(),
+
+ transformDirection: function ( m ) {
+
+ // input: THREE.Matrix4 affine matrix
+ // vector interpreted as a direction
+
+ var x = this.x, y = this.y, z = this.z;
+ var e = m.elements;
+
+ this.x = e[ 0 ] * x + e[ 4 ] * y + e[ 8 ] * z;
+ this.y = e[ 1 ] * x + e[ 5 ] * y + e[ 9 ] * z;
+ this.z = e[ 2 ] * x + e[ 6 ] * y + e[ 10 ] * z;
+
+ return this.normalize();
+
+ },
+
+ divide: function ( v ) {
+
+ this.x /= v.x;
+ this.y /= v.y;
+ this.z /= v.z;
+
+ return this;
+
+ },
+
+ divideScalar: function ( scalar ) {
+
+ return this.multiplyScalar( 1 / scalar );
+
+ },
+
+ min: function ( v ) {
+
+ this.x = Math.min( this.x, v.x );
+ this.y = Math.min( this.y, v.y );
+ this.z = Math.min( this.z, v.z );
+
+ return this;
+
+ },
+
+ max: function ( v ) {
+
+ this.x = Math.max( this.x, v.x );
+ this.y = Math.max( this.y, v.y );
+ this.z = Math.max( this.z, v.z );
+
+ return this;
+
+ },
+
+ clamp: function ( min, max ) {
+
+ // assumes min < max, componentwise
+
+ this.x = Math.max( min.x, Math.min( max.x, this.x ) );
+ this.y = Math.max( min.y, Math.min( max.y, this.y ) );
+ this.z = Math.max( min.z, Math.min( max.z, this.z ) );
+
+ return this;
+
+ },
+
+ clampScalar: function () {
+
+ var min = new Vector3();
+ var max = new Vector3();
+
+ return function clampScalar( minVal, maxVal ) {
+
+ min.set( minVal, minVal, minVal );
+ max.set( maxVal, maxVal, maxVal );
+
+ return this.clamp( min, max );
+
+ };
+
+ }(),
+
+ clampLength: function ( min, max ) {
+
+ var length = this.length();
+
+ return this.divideScalar( length || 1 ).multiplyScalar( Math.max( min, Math.min( max, length ) ) );
+
+ },
+
+ floor: function () {
+
+ this.x = Math.floor( this.x );
+ this.y = Math.floor( this.y );
+ this.z = Math.floor( this.z );
+
+ return this;
+
+ },
+
+ ceil: function () {
+
+ this.x = Math.ceil( this.x );
+ this.y = Math.ceil( this.y );
+ this.z = Math.ceil( this.z );
+
+ return this;
+
+ },
+
+ round: function () {
+
+ this.x = Math.round( this.x );
+ this.y = Math.round( this.y );
+ this.z = Math.round( this.z );
+
+ return this;
+
+ },
+
+ roundToZero: function () {
+
+ this.x = ( this.x < 0 ) ? Math.ceil( this.x ) : Math.floor( this.x );
+ this.y = ( this.y < 0 ) ? Math.ceil( this.y ) : Math.floor( this.y );
+ this.z = ( this.z < 0 ) ? Math.ceil( this.z ) : Math.floor( this.z );
+
+ return this;
+
+ },
+
+ negate: function () {
+
+ this.x = - this.x;
+ this.y = - this.y;
+ this.z = - this.z;
+
+ return this;
+
+ },
+
+ dot: function ( v ) {
+
+ return this.x * v.x + this.y * v.y + this.z * v.z;
+
+ },
+
+ // TODO lengthSquared?
+
+ lengthSq: function () {
+
+ return this.x * this.x + this.y * this.y + this.z * this.z;
+
+ },
+
+ length: function () {
+
+ return Math.sqrt( this.x * this.x + this.y * this.y + this.z * this.z );
+
+ },
+
+ manhattanLength: function () {
+
+ return Math.abs( this.x ) + Math.abs( this.y ) + Math.abs( this.z );
+
+ },
+
+ normalize: function () {
+
+ return this.divideScalar( this.length() || 1 );
+
+ },
+
+ setLength: function ( length ) {
+
+ return this.normalize().multiplyScalar( length );
+
+ },
+
+ lerp: function ( v, alpha ) {
+
+ this.x += ( v.x - this.x ) * alpha;
+ this.y += ( v.y - this.y ) * alpha;
+ this.z += ( v.z - this.z ) * alpha;
+
+ return this;
+
+ },
+
+ lerpVectors: function ( v1, v2, alpha ) {
+
+ return this.subVectors( v2, v1 ).multiplyScalar( alpha ).add( v1 );
+
+ },
+
+ cross: function ( v, w ) {
+
+ if ( w !== undefined ) {
+
+ console.warn( 'THREE.Vector3: .cross() now only accepts one argument. Use .crossVectors( a, b ) instead.' );
+ return this.crossVectors( v, w );
+
+ }
+
+ return this.crossVectors( this, v );
+
+ },
+
+ crossVectors: function ( a, b ) {
+
+ var ax = a.x, ay = a.y, az = a.z;
+ var bx = b.x, by = b.y, bz = b.z;
+
+ this.x = ay * bz - az * by;
+ this.y = az * bx - ax * bz;
+ this.z = ax * by - ay * bx;
+
+ return this;
+
+ },
+
+ projectOnVector: function ( vector ) {
+
+ var scalar = vector.dot( this ) / vector.lengthSq();
+
+ return this.copy( vector ).multiplyScalar( scalar );
+
+ },
+
+ projectOnPlane: function () {
+
+ var v1 = new Vector3();
+
+ return function projectOnPlane( planeNormal ) {
+
+ v1.copy( this ).projectOnVector( planeNormal );
+
+ return this.sub( v1 );
+
+ };
+
+ }(),
+
+ reflect: function () {
+
+ // reflect incident vector off plane orthogonal to normal
+ // normal is assumed to have unit length
+
+ var v1 = new Vector3();
+
+ return function reflect( normal ) {
+
+ return this.sub( v1.copy( normal ).multiplyScalar( 2 * this.dot( normal ) ) );
+
+ };
+
+ }(),
+
+ angleTo: function ( v ) {
+
+ var theta = this.dot( v ) / ( Math.sqrt( this.lengthSq() * v.lengthSq() ) );
+
+ // clamp, to handle numerical problems
+
+ return Math.acos( _Math.clamp( theta, - 1, 1 ) );
+
+ },
+
+ distanceTo: function ( v ) {
+
+ return Math.sqrt( this.distanceToSquared( v ) );
+
+ },
+
+ distanceToSquared: function ( v ) {
+
+ var dx = this.x - v.x, dy = this.y - v.y, dz = this.z - v.z;
+
+ return dx * dx + dy * dy + dz * dz;
+
+ },
+
+ manhattanDistanceTo: function ( v ) {
+
+ return Math.abs( this.x - v.x ) + Math.abs( this.y - v.y ) + Math.abs( this.z - v.z );
+
+ },
+
+ setFromSpherical: function ( s ) {
+
+ var sinPhiRadius = Math.sin( s.phi ) * s.radius;
+
+ this.x = sinPhiRadius * Math.sin( s.theta );
+ this.y = Math.cos( s.phi ) * s.radius;
+ this.z = sinPhiRadius * Math.cos( s.theta );
+
+ return this;
+
+ },
+
+ setFromCylindrical: function ( c ) {
+
+ this.x = c.radius * Math.sin( c.theta );
+ this.y = c.y;
+ this.z = c.radius * Math.cos( c.theta );
+
+ return this;
+
+ },
+
+ setFromMatrixPosition: function ( m ) {
+
+ var e = m.elements;
+
+ this.x = e[ 12 ];
+ this.y = e[ 13 ];
+ this.z = e[ 14 ];
+
+ return this;
+
+ },
+
+ setFromMatrixScale: function ( m ) {
+
+ var sx = this.setFromMatrixColumn( m, 0 ).length();
+ var sy = this.setFromMatrixColumn( m, 1 ).length();
+ var sz = this.setFromMatrixColumn( m, 2 ).length();
+
+ this.x = sx;
+ this.y = sy;
+ this.z = sz;
+
+ return this;
+
+ },
+
+ setFromMatrixColumn: function ( m, index ) {
+
+ return this.fromArray( m.elements, index * 4 );
+
+ },
+
+ equals: function ( v ) {
+
+ return ( ( v.x === this.x ) && ( v.y === this.y ) && ( v.z === this.z ) );
+
+ },
+
+ fromArray: function ( array, offset ) {
+
+ if ( offset === undefined ) offset = 0;
+
+ this.x = array[ offset ];
+ this.y = array[ offset + 1 ];
+ this.z = array[ offset + 2 ];
+
+ return this;
+
+ },
+
+ toArray: function ( array, offset ) {
+
+ if ( array === undefined ) array = [];
+ if ( offset === undefined ) offset = 0;
+
+ array[ offset ] = this.x;
+ array[ offset + 1 ] = this.y;
+ array[ offset + 2 ] = this.z;
+
+ return array;
+
+ },
+
+ fromBufferAttribute: function ( attribute, index, offset ) {
+
+ if ( offset !== undefined ) {
+
+ console.warn( 'THREE.Vector3: offset has been removed from .fromBufferAttribute().' );
+
+ }
+
+ this.x = attribute.getX( index );
+ this.y = attribute.getY( index );
+ this.z = attribute.getZ( index );
+
+ return this;
+
+ }
+
+} );
+
+/**
+ * @author alteredq / http://alteredqualia.com/
+ * @author WestLangley / http://github.com/WestLangley
+ * @author bhouston / http://clara.io
+ * @author tschw
+ */
+
+function Matrix3() {
+
+ this.elements = [
+
+ 1, 0, 0,
+ 0, 1, 0,
+ 0, 0, 1
+
+ ];
+
+ if ( arguments.length > 0 ) {
+
+ console.error( 'THREE.Matrix3: the constructor no longer reads arguments. use .set() instead.' );
+
+ }
+
+}
+
+Object.assign( Matrix3.prototype, {
+
+ isMatrix3: true,
+
+ set: function ( n11, n12, n13, n21, n22, n23, n31, n32, n33 ) {
+
+ var te = this.elements;
+
+ te[ 0 ] = n11; te[ 1 ] = n21; te[ 2 ] = n31;
+ te[ 3 ] = n12; te[ 4 ] = n22; te[ 5 ] = n32;
+ te[ 6 ] = n13; te[ 7 ] = n23; te[ 8 ] = n33;
+
+ return this;
+
+ },
+
+ identity: function () {
+
+ this.set(
+
+ 1, 0, 0,
+ 0, 1, 0,
+ 0, 0, 1
+
+ );
+
+ return this;
+
+ },
+
+ clone: function () {
+
+ return new this.constructor().fromArray( this.elements );
+
+ },
+
+ copy: function ( m ) {
+
+ var te = this.elements;
+ var me = m.elements;
+
+ te[ 0 ] = me[ 0 ]; te[ 1 ] = me[ 1 ]; te[ 2 ] = me[ 2 ];
+ te[ 3 ] = me[ 3 ]; te[ 4 ] = me[ 4 ]; te[ 5 ] = me[ 5 ];
+ te[ 6 ] = me[ 6 ]; te[ 7 ] = me[ 7 ]; te[ 8 ] = me[ 8 ];
+
+ return this;
+
+ },
+
+ setFromMatrix4: function ( m ) {
+
+ var me = m.elements;
+
+ this.set(
+
+ me[ 0 ], me[ 4 ], me[ 8 ],
+ me[ 1 ], me[ 5 ], me[ 9 ],
+ me[ 2 ], me[ 6 ], me[ 10 ]
+
+ );
+
+ return this;
+
+ },
+
+ applyToBufferAttribute: function () {
+
+ var v1 = new Vector3();
+
+ return function applyToBufferAttribute( attribute ) {
+
+ for ( var i = 0, l = attribute.count; i < l; i ++ ) {
+
+ v1.x = attribute.getX( i );
+ v1.y = attribute.getY( i );
+ v1.z = attribute.getZ( i );
+
+ v1.applyMatrix3( this );
+
+ attribute.setXYZ( i, v1.x, v1.y, v1.z );
+
+ }
+
+ return attribute;
+
+ };
+
+ }(),
+
+ multiply: function ( m ) {
+
+ return this.multiplyMatrices( this, m );
+
+ },
+
+ premultiply: function ( m ) {
+
+ return this.multiplyMatrices( m, this );
+
+ },
+
+ multiplyMatrices: function ( a, b ) {
+
+ var ae = a.elements;
+ var be = b.elements;
+ var te = this.elements;
+
+ var a11 = ae[ 0 ], a12 = ae[ 3 ], a13 = ae[ 6 ];
+ var a21 = ae[ 1 ], a22 = ae[ 4 ], a23 = ae[ 7 ];
+ var a31 = ae[ 2 ], a32 = ae[ 5 ], a33 = ae[ 8 ];
+
+ var b11 = be[ 0 ], b12 = be[ 3 ], b13 = be[ 6 ];
+ var b21 = be[ 1 ], b22 = be[ 4 ], b23 = be[ 7 ];
+ var b31 = be[ 2 ], b32 = be[ 5 ], b33 = be[ 8 ];
+
+ te[ 0 ] = a11 * b11 + a12 * b21 + a13 * b31;
+ te[ 3 ] = a11 * b12 + a12 * b22 + a13 * b32;
+ te[ 6 ] = a11 * b13 + a12 * b23 + a13 * b33;
+
+ te[ 1 ] = a21 * b11 + a22 * b21 + a23 * b31;
+ te[ 4 ] = a21 * b12 + a22 * b22 + a23 * b32;
+ te[ 7 ] = a21 * b13 + a22 * b23 + a23 * b33;
+
+ te[ 2 ] = a31 * b11 + a32 * b21 + a33 * b31;
+ te[ 5 ] = a31 * b12 + a32 * b22 + a33 * b32;
+ te[ 8 ] = a31 * b13 + a32 * b23 + a33 * b33;
+
+ return this;
+
+ },
+
+ multiplyScalar: function ( s ) {
+
+ var te = this.elements;
+
+ te[ 0 ] *= s; te[ 3 ] *= s; te[ 6 ] *= s;
+ te[ 1 ] *= s; te[ 4 ] *= s; te[ 7 ] *= s;
+ te[ 2 ] *= s; te[ 5 ] *= s; te[ 8 ] *= s;
+
+ return this;
+
+ },
+
+ determinant: function () {
+
+ var te = this.elements;
+
+ var a = te[ 0 ], b = te[ 1 ], c = te[ 2 ],
+ d = te[ 3 ], e = te[ 4 ], f = te[ 5 ],
+ g = te[ 6 ], h = te[ 7 ], i = te[ 8 ];
+
+ return a * e * i - a * f * h - b * d * i + b * f * g + c * d * h - c * e * g;
+
+ },
+
+ getInverse: function ( matrix, throwOnDegenerate ) {
+
+ if ( matrix && matrix.isMatrix4 ) {
+
+ console.error( "THREE.Matrix3: .getInverse() no longer takes a Matrix4 argument." );
+
+ }
+
+ var me = matrix.elements,
+ te = this.elements,
+
+ n11 = me[ 0 ], n21 = me[ 1 ], n31 = me[ 2 ],
+ n12 = me[ 3 ], n22 = me[ 4 ], n32 = me[ 5 ],
+ n13 = me[ 6 ], n23 = me[ 7 ], n33 = me[ 8 ],
+
+ t11 = n33 * n22 - n32 * n23,
+ t12 = n32 * n13 - n33 * n12,
+ t13 = n23 * n12 - n22 * n13,
+
+ det = n11 * t11 + n21 * t12 + n31 * t13;
+
+ if ( det === 0 ) {
+
+ var msg = "THREE.Matrix3: .getInverse() can't invert matrix, determinant is 0";
+
+ if ( throwOnDegenerate === true ) {
+
+ throw new Error( msg );
+
+ } else {
+
+ console.warn( msg );
+
+ }
+
+ return this.identity();
+
+ }
+
+ var detInv = 1 / det;
+
+ te[ 0 ] = t11 * detInv;
+ te[ 1 ] = ( n31 * n23 - n33 * n21 ) * detInv;
+ te[ 2 ] = ( n32 * n21 - n31 * n22 ) * detInv;
+
+ te[ 3 ] = t12 * detInv;
+ te[ 4 ] = ( n33 * n11 - n31 * n13 ) * detInv;
+ te[ 5 ] = ( n31 * n12 - n32 * n11 ) * detInv;
+
+ te[ 6 ] = t13 * detInv;
+ te[ 7 ] = ( n21 * n13 - n23 * n11 ) * detInv;
+ te[ 8 ] = ( n22 * n11 - n21 * n12 ) * detInv;
+
+ return this;
+
+ },
+
+ transpose: function () {
+
+ var tmp, m = this.elements;
+
+ tmp = m[ 1 ]; m[ 1 ] = m[ 3 ]; m[ 3 ] = tmp;
+ tmp = m[ 2 ]; m[ 2 ] = m[ 6 ]; m[ 6 ] = tmp;
+ tmp = m[ 5 ]; m[ 5 ] = m[ 7 ]; m[ 7 ] = tmp;
+
+ return this;
+
+ },
+
+ getNormalMatrix: function ( matrix4 ) {
+
+ return this.setFromMatrix4( matrix4 ).getInverse( this ).transpose();
+
+ },
+
+ transposeIntoArray: function ( r ) {
+
+ var m = this.elements;
+
+ r[ 0 ] = m[ 0 ];
+ r[ 1 ] = m[ 3 ];
+ r[ 2 ] = m[ 6 ];
+ r[ 3 ] = m[ 1 ];
+ r[ 4 ] = m[ 4 ];
+ r[ 5 ] = m[ 7 ];
+ r[ 6 ] = m[ 2 ];
+ r[ 7 ] = m[ 5 ];
+ r[ 8 ] = m[ 8 ];
+
+ return this;
+
+ },
+
+ setUvTransform: function ( tx, ty, sx, sy, rotation, cx, cy ) {
+
+ var c = Math.cos( rotation );
+ var s = Math.sin( rotation );
+
+ this.set(
+ sx * c, sx * s, - sx * ( c * cx + s * cy ) + cx + tx,
+ - sy * s, sy * c, - sy * ( - s * cx + c * cy ) + cy + ty,
+ 0, 0, 1
+ );
+
+ },
+
+ scale: function ( sx, sy ) {
+
+ var te = this.elements;
+
+ te[ 0 ] *= sx; te[ 3 ] *= sx; te[ 6 ] *= sx;
+ te[ 1 ] *= sy; te[ 4 ] *= sy; te[ 7 ] *= sy;
+
+ return this;
+
+ },
+
+ rotate: function ( theta ) {
+
+ var c = Math.cos( theta );
+ var s = Math.sin( theta );
+
+ var te = this.elements;
+
+ var a11 = te[ 0 ], a12 = te[ 3 ], a13 = te[ 6 ];
+ var a21 = te[ 1 ], a22 = te[ 4 ], a23 = te[ 7 ];
+
+ te[ 0 ] = c * a11 + s * a21;
+ te[ 3 ] = c * a12 + s * a22;
+ te[ 6 ] = c * a13 + s * a23;
+
+ te[ 1 ] = - s * a11 + c * a21;
+ te[ 4 ] = - s * a12 + c * a22;
+ te[ 7 ] = - s * a13 + c * a23;
+
+ return this;
+
+ },
+
+ translate: function ( tx, ty ) {
+
+ var te = this.elements;
+
+ te[ 0 ] += tx * te[ 2 ]; te[ 3 ] += tx * te[ 5 ]; te[ 6 ] += tx * te[ 8 ];
+ te[ 1 ] += ty * te[ 2 ]; te[ 4 ] += ty * te[ 5 ]; te[ 7 ] += ty * te[ 8 ];
+
+ return this;
+
+ },
+
+ equals: function ( matrix ) {
+
+ var te = this.elements;
+ var me = matrix.elements;
+
+ for ( var i = 0; i < 9; i ++ ) {
+
+ if ( te[ i ] !== me[ i ] ) return false;
+
+ }
+
+ return true;
+
+ },
+
+ fromArray: function ( array, offset ) {
+
+ if ( offset === undefined ) offset = 0;
+
+ for ( var i = 0; i < 9; i ++ ) {
+
+ this.elements[ i ] = array[ i + offset ];
+
+ }
+
+ return this;
+
+ },
+
+ toArray: function ( array, offset ) {
+
+ if ( array === undefined ) array = [];
+ if ( offset === undefined ) offset = 0;
+
+ var te = this.elements;
+
+ array[ offset ] = te[ 0 ];
+ array[ offset + 1 ] = te[ 1 ];
+ array[ offset + 2 ] = te[ 2 ];
+
+ array[ offset + 3 ] = te[ 3 ];
+ array[ offset + 4 ] = te[ 4 ];
+ array[ offset + 5 ] = te[ 5 ];
+
+ array[ offset + 6 ] = te[ 6 ];
+ array[ offset + 7 ] = te[ 7 ];
+ array[ offset + 8 ] = te[ 8 ];
+
+ return array;
+
+ }
+
+} );
+
+/**
+ * @author mrdoob / http://mrdoob.com/
+ * @author alteredq / http://alteredqualia.com/
+ * @author szimek / https://github.com/szimek/
+ */
+
+var textureId = 0;
+
+function Texture( image, mapping, wrapS, wrapT, magFilter, minFilter, format, type, anisotropy, encoding ) {
+
+ Object.defineProperty( this, 'id', { value: textureId ++ } );
+
+ this.uuid = _Math.generateUUID();
+
+ this.name = '';
+
+ this.image = image !== undefined ? image : Texture.DEFAULT_IMAGE;
+ this.mipmaps = [];
+
+ this.mapping = mapping !== undefined ? mapping : Texture.DEFAULT_MAPPING;
+
+ this.wrapS = wrapS !== undefined ? wrapS : ClampToEdgeWrapping;
+ this.wrapT = wrapT !== undefined ? wrapT : ClampToEdgeWrapping;
+
+ this.magFilter = magFilter !== undefined ? magFilter : LinearFilter;
+ this.minFilter = minFilter !== undefined ? minFilter : LinearMipMapLinearFilter;
+
+ this.anisotropy = anisotropy !== undefined ? anisotropy : 1;
+
+ this.format = format !== undefined ? format : RGBAFormat;
+ this.type = type !== undefined ? type : UnsignedByteType;
+
+ this.offset = new Vector2( 0, 0 );
+ this.repeat = new Vector2( 1, 1 );
+ this.center = new Vector2( 0, 0 );
+ this.rotation = 0;
+
+ this.matrixAutoUpdate = true;
+ this.matrix = new Matrix3();
+
+ this.generateMipmaps = true;
+ this.premultiplyAlpha = false;
+ this.flipY = true;
+ this.unpackAlignment = 4; // valid values: 1, 2, 4, 8 (see http://www.khronos.org/opengles/sdk/docs/man/xhtml/glPixelStorei.xml)
+
+ // Values of encoding !== THREE.LinearEncoding only supported on map, envMap and emissiveMap.
+ //
+ // Also changing the encoding after already used by a Material will not automatically make the Material
+ // update. You need to explicitly call Material.needsUpdate to trigger it to recompile.
+ this.encoding = encoding !== undefined ? encoding : LinearEncoding;
+
+ this.version = 0;
+ this.onUpdate = null;
+
+}
+
+Texture.DEFAULT_IMAGE = undefined;
+Texture.DEFAULT_MAPPING = UVMapping;
+
+Texture.prototype = Object.assign( Object.create( EventDispatcher.prototype ), {
+
+ constructor: Texture,
+
+ isTexture: true,
+
+ clone: function () {
+
+ return new this.constructor().copy( this );
+
+ },
+
+ copy: function ( source ) {
+
+ this.name = source.name;
+
+ this.image = source.image;
+ this.mipmaps = source.mipmaps.slice( 0 );
+
+ this.mapping = source.mapping;
+
+ this.wrapS = source.wrapS;
+ this.wrapT = source.wrapT;
+
+ this.magFilter = source.magFilter;
+ this.minFilter = source.minFilter;
+
+ this.anisotropy = source.anisotropy;
+
+ this.format = source.format;
+ this.type = source.type;
+
+ this.offset.copy( source.offset );
+ this.repeat.copy( source.repeat );
+ this.center.copy( source.center );
+ this.rotation = source.rotation;
+
+ this.matrixAutoUpdate = source.matrixAutoUpdate;
+ this.matrix.copy( source.matrix );
+
+ this.generateMipmaps = source.generateMipmaps;
+ this.premultiplyAlpha = source.premultiplyAlpha;
+ this.flipY = source.flipY;
+ this.unpackAlignment = source.unpackAlignment;
+ this.encoding = source.encoding;
+
+ return this;
+
+ },
+
+ toJSON: function ( meta ) {
+
+ var isRootObject = ( meta === undefined || typeof meta === 'string' );
+
+ if ( ! isRootObject && meta.textures[ this.uuid ] !== undefined ) {
+
+ return meta.textures[ this.uuid ];
+
+ }
+
+ function getDataURL( image ) {
+
+ var canvas;
+
+ if ( image instanceof HTMLCanvasElement ) {
+
+ canvas = image;
+
+ } else {
+
+ canvas = document.createElementNS( 'http://www.w3.org/1999/xhtml', 'canvas' );
+ canvas.width = image.width;
+ canvas.height = image.height;
+
+ var context = canvas.getContext( '2d' );
+
+ if ( image instanceof ImageData ) {
+
+ context.putImageData( image, 0, 0 );
+
+ } else {
+
+ context.drawImage( image, 0, 0, image.width, image.height );
+
+ }
+
+ }
+
+ if ( canvas.width > 2048 || canvas.height > 2048 ) {
+
+ return canvas.toDataURL( 'image/jpeg', 0.6 );
+
+ } else {
+
+ return canvas.toDataURL( 'image/png' );
+
+ }
+
+ }
+
+ var output = {
+ metadata: {
+ version: 4.5,
+ type: 'Texture',
+ generator: 'Texture.toJSON'
+ },
+
+ uuid: this.uuid,
+ name: this.name,
+
+ mapping: this.mapping,
+
+ repeat: [ this.repeat.x, this.repeat.y ],
+ offset: [ this.offset.x, this.offset.y ],
+ center: [ this.center.x, this.center.y ],
+ rotation: this.rotation,
+
+ wrap: [ this.wrapS, this.wrapT ],
+
+ minFilter: this.minFilter,
+ magFilter: this.magFilter,
+ anisotropy: this.anisotropy,
+
+ flipY: this.flipY
+ };
+
+ if ( this.image !== undefined ) {
+
+ // TODO: Move to THREE.Image
+
+ var image = this.image;
+
+ if ( image.uuid === undefined ) {
+
+ image.uuid = _Math.generateUUID(); // UGH
+
+ }
+
+ if ( ! isRootObject && meta.images[ image.uuid ] === undefined ) {
+
+ meta.images[ image.uuid ] = {
+ uuid: image.uuid,
+ url: getDataURL( image )
+ };
+
+ }
+
+ output.image = image.uuid;
+
+ }
+
+ if ( ! isRootObject ) {
+
+ meta.textures[ this.uuid ] = output;
+
+ }
+
+ return output;
+
+ },
+
+ dispose: function () {
+
+ this.dispatchEvent( { type: 'dispose' } );
+
+ },
+
+ transformUv: function ( uv ) {
+
+ if ( this.mapping !== UVMapping ) return;
+
+ uv.applyMatrix3( this.matrix );
+
+ if ( uv.x < 0 || uv.x > 1 ) {
+
+ switch ( this.wrapS ) {
+
+ case RepeatWrapping:
+
+ uv.x = uv.x - Math.floor( uv.x );
+ break;
+
+ case ClampToEdgeWrapping:
+
+ uv.x = uv.x < 0 ? 0 : 1;
+ break;
+
+ case MirroredRepeatWrapping:
+
+ if ( Math.abs( Math.floor( uv.x ) % 2 ) === 1 ) {
+
+ uv.x = Math.ceil( uv.x ) - uv.x;
+
+ } else {
+
+ uv.x = uv.x - Math.floor( uv.x );
+
+ }
+ break;
+
+ }
+
+ }
+
+ if ( uv.y < 0 || uv.y > 1 ) {
+
+ switch ( this.wrapT ) {
+
+ case RepeatWrapping:
+
+ uv.y = uv.y - Math.floor( uv.y );
+ break;
+
+ case ClampToEdgeWrapping:
+
+ uv.y = uv.y < 0 ? 0 : 1;
+ break;
+
+ case MirroredRepeatWrapping:
+
+ if ( Math.abs( Math.floor( uv.y ) % 2 ) === 1 ) {
+
+ uv.y = Math.ceil( uv.y ) - uv.y;
+
+ } else {
+
+ uv.y = uv.y - Math.floor( uv.y );
+
+ }
+ break;
+
+ }
+
+ }
+
+ if ( this.flipY ) {
+
+ uv.y = 1 - uv.y;
+
+ }
+
+ }
+
+} );
+
+Object.defineProperty( Texture.prototype, "needsUpdate", {
+
+ set: function ( value ) {
+
+ if ( value === true ) this.version ++;
+
+ }
+
+} );
+
+/**
+ * @author supereggbert / http://www.paulbrunt.co.uk/
+ * @author philogb / http://blog.thejit.org/
+ * @author mikael emtinger / http://gomo.se/
+ * @author egraether / http://egraether.com/
+ * @author WestLangley / http://github.com/WestLangley
+ */
+
+function Vector4( x, y, z, w ) {
+
+ this.x = x || 0;
+ this.y = y || 0;
+ this.z = z || 0;
+ this.w = ( w !== undefined ) ? w : 1;
+
+}
+
+Object.assign( Vector4.prototype, {
+
+ isVector4: true,
+
+ set: function ( x, y, z, w ) {
+
+ this.x = x;
+ this.y = y;
+ this.z = z;
+ this.w = w;
+
+ return this;
+
+ },
+
+ setScalar: function ( scalar ) {
+
+ this.x = scalar;
+ this.y = scalar;
+ this.z = scalar;
+ this.w = scalar;
+
+ return this;
+
+ },
+
+ setX: function ( x ) {
+
+ this.x = x;
+
+ return this;
+
+ },
+
+ setY: function ( y ) {
+
+ this.y = y;
+
+ return this;
+
+ },
+
+ setZ: function ( z ) {
+
+ this.z = z;
+
+ return this;
+
+ },
+
+ setW: function ( w ) {
+
+ this.w = w;
+
+ return this;
+
+ },
+
+ setComponent: function ( index, value ) {
+
+ switch ( index ) {
+
+ case 0: this.x = value; break;
+ case 1: this.y = value; break;
+ case 2: this.z = value; break;
+ case 3: this.w = value; break;
+ default: throw new Error( 'index is out of range: ' + index );
+
+ }
+
+ return this;
+
+ },
+
+ getComponent: function ( index ) {
+
+ switch ( index ) {
+
+ case 0: return this.x;
+ case 1: return this.y;
+ case 2: return this.z;
+ case 3: return this.w;
+ default: throw new Error( 'index is out of range: ' + index );
+
+ }
+
+ },
+
+ clone: function () {
+
+ return new this.constructor( this.x, this.y, this.z, this.w );
+
+ },
+
+ copy: function ( v ) {
+
+ this.x = v.x;
+ this.y = v.y;
+ this.z = v.z;
+ this.w = ( v.w !== undefined ) ? v.w : 1;
+
+ return this;
+
+ },
+
+ add: function ( v, w ) {
+
+ if ( w !== undefined ) {
+
+ console.warn( 'THREE.Vector4: .add() now only accepts one argument. Use .addVectors( a, b ) instead.' );
+ return this.addVectors( v, w );
+
+ }
+
+ this.x += v.x;
+ this.y += v.y;
+ this.z += v.z;
+ this.w += v.w;
+
+ return this;
+
+ },
+
+ addScalar: function ( s ) {
+
+ this.x += s;
+ this.y += s;
+ this.z += s;
+ this.w += s;
+
+ return this;
+
+ },
+
+ addVectors: function ( a, b ) {
+
+ this.x = a.x + b.x;
+ this.y = a.y + b.y;
+ this.z = a.z + b.z;
+ this.w = a.w + b.w;
+
+ return this;
+
+ },
+
+ addScaledVector: function ( v, s ) {
+
+ this.x += v.x * s;
+ this.y += v.y * s;
+ this.z += v.z * s;
+ this.w += v.w * s;
+
+ return this;
+
+ },
+
+ sub: function ( v, w ) {
+
+ if ( w !== undefined ) {
+
+ console.warn( 'THREE.Vector4: .sub() now only accepts one argument. Use .subVectors( a, b ) instead.' );
+ return this.subVectors( v, w );
+
+ }
+
+ this.x -= v.x;
+ this.y -= v.y;
+ this.z -= v.z;
+ this.w -= v.w;
+
+ return this;
+
+ },
+
+ subScalar: function ( s ) {
+
+ this.x -= s;
+ this.y -= s;
+ this.z -= s;
+ this.w -= s;
+
+ return this;
+
+ },
+
+ subVectors: function ( a, b ) {
+
+ this.x = a.x - b.x;
+ this.y = a.y - b.y;
+ this.z = a.z - b.z;
+ this.w = a.w - b.w;
+
+ return this;
+
+ },
+
+ multiplyScalar: function ( scalar ) {
+
+ this.x *= scalar;
+ this.y *= scalar;
+ this.z *= scalar;
+ this.w *= scalar;
+
+ return this;
+
+ },
+
+ applyMatrix4: function ( m ) {
+
+ var x = this.x, y = this.y, z = this.z, w = this.w;
+ var e = m.elements;
+
+ this.x = e[ 0 ] * x + e[ 4 ] * y + e[ 8 ] * z + e[ 12 ] * w;
+ this.y = e[ 1 ] * x + e[ 5 ] * y + e[ 9 ] * z + e[ 13 ] * w;
+ this.z = e[ 2 ] * x + e[ 6 ] * y + e[ 10 ] * z + e[ 14 ] * w;
+ this.w = e[ 3 ] * x + e[ 7 ] * y + e[ 11 ] * z + e[ 15 ] * w;
+
+ return this;
+
+ },
+
+ divideScalar: function ( scalar ) {
+
+ return this.multiplyScalar( 1 / scalar );
+
+ },
+
+ setAxisAngleFromQuaternion: function ( q ) {
+
+ // http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToAngle/index.htm
+
+ // q is assumed to be normalized
+
+ this.w = 2 * Math.acos( q.w );
+
+ var s = Math.sqrt( 1 - q.w * q.w );
+
+ if ( s < 0.0001 ) {
+
+ this.x = 1;
+ this.y = 0;
+ this.z = 0;
+
+ } else {
+
+ this.x = q.x / s;
+ this.y = q.y / s;
+ this.z = q.z / s;
+
+ }
+
+ return this;
+
+ },
+
+ setAxisAngleFromRotationMatrix: function ( m ) {
+
+ // http://www.euclideanspace.com/maths/geometry/rotations/conversions/matrixToAngle/index.htm
+
+ // assumes the upper 3x3 of m is a pure rotation matrix (i.e, unscaled)
+
+ var angle, x, y, z, // variables for result
+ epsilon = 0.01, // margin to allow for rounding errors
+ epsilon2 = 0.1, // margin to distinguish between 0 and 180 degrees
+
+ te = m.elements,
+
+ m11 = te[ 0 ], m12 = te[ 4 ], m13 = te[ 8 ],
+ m21 = te[ 1 ], m22 = te[ 5 ], m23 = te[ 9 ],
+ m31 = te[ 2 ], m32 = te[ 6 ], m33 = te[ 10 ];
+
+ if ( ( Math.abs( m12 - m21 ) < epsilon ) &&
+ ( Math.abs( m13 - m31 ) < epsilon ) &&
+ ( Math.abs( m23 - m32 ) < epsilon ) ) {
+
+ // singularity found
+ // first check for identity matrix which must have +1 for all terms
+ // in leading diagonal and zero in other terms
+
+ if ( ( Math.abs( m12 + m21 ) < epsilon2 ) &&
+ ( Math.abs( m13 + m31 ) < epsilon2 ) &&
+ ( Math.abs( m23 + m32 ) < epsilon2 ) &&
+ ( Math.abs( m11 + m22 + m33 - 3 ) < epsilon2 ) ) {
+
+ // this singularity is identity matrix so angle = 0
+
+ this.set( 1, 0, 0, 0 );
+
+ return this; // zero angle, arbitrary axis
+
+ }
+
+ // otherwise this singularity is angle = 180
+
+ angle = Math.PI;
+
+ var xx = ( m11 + 1 ) / 2;
+ var yy = ( m22 + 1 ) / 2;
+ var zz = ( m33 + 1 ) / 2;
+ var xy = ( m12 + m21 ) / 4;
+ var xz = ( m13 + m31 ) / 4;
+ var yz = ( m23 + m32 ) / 4;
+
+ if ( ( xx > yy ) && ( xx > zz ) ) {
+
+ // m11 is the largest diagonal term
+
+ if ( xx < epsilon ) {
+
+ x = 0;
+ y = 0.707106781;
+ z = 0.707106781;
+
+ } else {
+
+ x = Math.sqrt( xx );
+ y = xy / x;
+ z = xz / x;
+
+ }
+
+ } else if ( yy > zz ) {
+
+ // m22 is the largest diagonal term
+
+ if ( yy < epsilon ) {
+
+ x = 0.707106781;
+ y = 0;
+ z = 0.707106781;
+
+ } else {
+
+ y = Math.sqrt( yy );
+ x = xy / y;
+ z = yz / y;
+
+ }
+
+ } else {
+
+ // m33 is the largest diagonal term so base result on this
+
+ if ( zz < epsilon ) {
+
+ x = 0.707106781;
+ y = 0.707106781;
+ z = 0;
+
+ } else {
+
+ z = Math.sqrt( zz );
+ x = xz / z;
+ y = yz / z;
+
+ }
+
+ }
+
+ this.set( x, y, z, angle );
+
+ return this; // return 180 deg rotation
+
+ }
+
+ // as we have reached here there are no singularities so we can handle normally
+
+ var s = Math.sqrt( ( m32 - m23 ) * ( m32 - m23 ) +
+ ( m13 - m31 ) * ( m13 - m31 ) +
+ ( m21 - m12 ) * ( m21 - m12 ) ); // used to normalize
+
+ if ( Math.abs( s ) < 0.001 ) s = 1;
+
+ // prevent divide by zero, should not happen if matrix is orthogonal and should be
+ // caught by singularity test above, but I've left it in just in case
+
+ this.x = ( m32 - m23 ) / s;
+ this.y = ( m13 - m31 ) / s;
+ this.z = ( m21 - m12 ) / s;
+ this.w = Math.acos( ( m11 + m22 + m33 - 1 ) / 2 );
+
+ return this;
+
+ },
+
+ min: function ( v ) {
+
+ this.x = Math.min( this.x, v.x );
+ this.y = Math.min( this.y, v.y );
+ this.z = Math.min( this.z, v.z );
+ this.w = Math.min( this.w, v.w );
+
+ return this;
+
+ },
+
+ max: function ( v ) {
+
+ this.x = Math.max( this.x, v.x );
+ this.y = Math.max( this.y, v.y );
+ this.z = Math.max( this.z, v.z );
+ this.w = Math.max( this.w, v.w );
+
+ return this;
+
+ },
+
+ clamp: function ( min, max ) {
+
+ // assumes min < max, componentwise
+
+ this.x = Math.max( min.x, Math.min( max.x, this.x ) );
+ this.y = Math.max( min.y, Math.min( max.y, this.y ) );
+ this.z = Math.max( min.z, Math.min( max.z, this.z ) );
+ this.w = Math.max( min.w, Math.min( max.w, this.w ) );
+
+ return this;
+
+ },
+
+ clampScalar: function () {
+
+ var min, max;
+
+ return function clampScalar( minVal, maxVal ) {
+
+ if ( min === undefined ) {
+
+ min = new Vector4();
+ max = new Vector4();
+
+ }
+
+ min.set( minVal, minVal, minVal, minVal );
+ max.set( maxVal, maxVal, maxVal, maxVal );
+
+ return this.clamp( min, max );
+
+ };
+
+ }(),
+
+ clampLength: function ( min, max ) {
+
+ var length = this.length();
+
+ return this.divideScalar( length || 1 ).multiplyScalar( Math.max( min, Math.min( max, length ) ) );
+
+ },
+
+ floor: function () {
+
+ this.x = Math.floor( this.x );
+ this.y = Math.floor( this.y );
+ this.z = Math.floor( this.z );
+ this.w = Math.floor( this.w );
+
+ return this;
+
+ },
+
+ ceil: function () {
+
+ this.x = Math.ceil( this.x );
+ this.y = Math.ceil( this.y );
+ this.z = Math.ceil( this.z );
+ this.w = Math.ceil( this.w );
+
+ return this;
+
+ },
+
+ round: function () {
+
+ this.x = Math.round( this.x );
+ this.y = Math.round( this.y );
+ this.z = Math.round( this.z );
+ this.w = Math.round( this.w );
+
+ return this;
+
+ },
+
+ roundToZero: function () {
+
+ this.x = ( this.x < 0 ) ? Math.ceil( this.x ) : Math.floor( this.x );
+ this.y = ( this.y < 0 ) ? Math.ceil( this.y ) : Math.floor( this.y );
+ this.z = ( this.z < 0 ) ? Math.ceil( this.z ) : Math.floor( this.z );
+ this.w = ( this.w < 0 ) ? Math.ceil( this.w ) : Math.floor( this.w );
+
+ return this;
+
+ },
+
+ negate: function () {
+
+ this.x = - this.x;
+ this.y = - this.y;
+ this.z = - this.z;
+ this.w = - this.w;
+
+ return this;
+
+ },
+
+ dot: function ( v ) {
+
+ return this.x * v.x + this.y * v.y + this.z * v.z + this.w * v.w;
+
+ },
+
+ lengthSq: function () {
+
+ return this.x * this.x + this.y * this.y + this.z * this.z + this.w * this.w;
+
+ },
+
+ length: function () {
+
+ return Math.sqrt( this.x * this.x + this.y * this.y + this.z * this.z + this.w * this.w );
+
+ },
+
+ manhattanLength: function () {
+
+ return Math.abs( this.x ) + Math.abs( this.y ) + Math.abs( this.z ) + Math.abs( this.w );
+
+ },
+
+ normalize: function () {
+
+ return this.divideScalar( this.length() || 1 );
+
+ },
+
+ setLength: function ( length ) {
+
+ return this.normalize().multiplyScalar( length );
+
+ },
+
+ lerp: function ( v, alpha ) {
+
+ this.x += ( v.x - this.x ) * alpha;
+ this.y += ( v.y - this.y ) * alpha;
+ this.z += ( v.z - this.z ) * alpha;
+ this.w += ( v.w - this.w ) * alpha;
+
+ return this;
+
+ },
+
+ lerpVectors: function ( v1, v2, alpha ) {
+
+ return this.subVectors( v2, v1 ).multiplyScalar( alpha ).add( v1 );
+
+ },
+
+ equals: function ( v ) {
+
+ return ( ( v.x === this.x ) && ( v.y === this.y ) && ( v.z === this.z ) && ( v.w === this.w ) );
+
+ },
+
+ fromArray: function ( array, offset ) {
+
+ if ( offset === undefined ) offset = 0;
+
+ this.x = array[ offset ];
+ this.y = array[ offset + 1 ];
+ this.z = array[ offset + 2 ];
+ this.w = array[ offset + 3 ];
+
+ return this;
+
+ },
+
+ toArray: function ( array, offset ) {
+
+ if ( array === undefined ) array = [];
+ if ( offset === undefined ) offset = 0;
+
+ array[ offset ] = this.x;
+ array[ offset + 1 ] = this.y;
+ array[ offset + 2 ] = this.z;
+ array[ offset + 3 ] = this.w;
+
+ return array;
+
+ },
+
+ fromBufferAttribute: function ( attribute, index, offset ) {
+
+ if ( offset !== undefined ) {
+
+ console.warn( 'THREE.Vector4: offset has been removed from .fromBufferAttribute().' );
+
+ }
+
+ this.x = attribute.getX( index );
+ this.y = attribute.getY( index );
+ this.z = attribute.getZ( index );
+ this.w = attribute.getW( index );
+
+ return this;
+
+ }
+
+} );
+
+/**
+ * @author szimek / https://github.com/szimek/
+ * @author alteredq / http://alteredqualia.com/
+ * @author Marius Kintel / https://github.com/kintel
+ */
+
+/*
+ In options, we can specify:
+ * Texture parameters for an auto-generated target texture
+ * depthBuffer/stencilBuffer: Booleans to indicate if we should generate these buffers
+*/
+function WebGLRenderTarget( width, height, options ) {
+
+ this.uuid = _Math.generateUUID();
+
+ this.width = width;
+ this.height = height;
+
+ this.scissor = new Vector4( 0, 0, width, height );
+ this.scissorTest = false;
+
+ this.viewport = new Vector4( 0, 0, width, height );
+
+ options = options || {};
+
+ if ( options.minFilter === undefined ) options.minFilter = LinearFilter;
+
+ this.texture = new Texture( undefined, undefined, options.wrapS, options.wrapT, options.magFilter, options.minFilter, options.format, options.type, options.anisotropy, options.encoding );
+
+ this.depthBuffer = options.depthBuffer !== undefined ? options.depthBuffer : true;
+ this.stencilBuffer = options.stencilBuffer !== undefined ? options.stencilBuffer : true;
+ this.depthTexture = options.depthTexture !== undefined ? options.depthTexture : null;
+
+}
+
+WebGLRenderTarget.prototype = Object.assign( Object.create( EventDispatcher.prototype ), {
+
+ constructor: WebGLRenderTarget,
+
+ isWebGLRenderTarget: true,
+
+ setSize: function ( width, height ) {
+
+ if ( this.width !== width || this.height !== height ) {
+
+ this.width = width;
+ this.height = height;
+
+ this.dispose();
+
+ }
+
+ this.viewport.set( 0, 0, width, height );
+ this.scissor.set( 0, 0, width, height );
+
+ },
+
+ clone: function () {
+
+ return new this.constructor().copy( this );
+
+ },
+
+ copy: function ( source ) {
+
+ this.width = source.width;
+ this.height = source.height;
+
+ this.viewport.copy( source.viewport );
+
+ this.texture = source.texture.clone();
+
+ this.depthBuffer = source.depthBuffer;
+ this.stencilBuffer = source.stencilBuffer;
+ this.depthTexture = source.depthTexture;
+
+ return this;
+
+ },
+
+ dispose: function () {
+
+ this.dispatchEvent( { type: 'dispose' } );
+
+ }
+
+} );
+
+/**
+ * @author alteredq / http://alteredqualia.com
+ */
+
+function WebGLRenderTargetCube( width, height, options ) {
+
+ WebGLRenderTarget.call( this, width, height, options );
+
+ this.activeCubeFace = 0; // PX 0, NX 1, PY 2, NY 3, PZ 4, NZ 5
+ this.activeMipMapLevel = 0;
+
+}
+
+WebGLRenderTargetCube.prototype = Object.create( WebGLRenderTarget.prototype );
+WebGLRenderTargetCube.prototype.constructor = WebGLRenderTargetCube;
+
+WebGLRenderTargetCube.prototype.isWebGLRenderTargetCube = true;
+
+/**
+ * @author alteredq / http://alteredqualia.com/
+ */
+
+function DataTexture( data, width, height, format, type, mapping, wrapS, wrapT, magFilter, minFilter, anisotropy, encoding ) {
+
+ Texture.call( this, null, mapping, wrapS, wrapT, magFilter, minFilter, format, type, anisotropy, encoding );
+
+ this.image = { data: data, width: width, height: height };
+
+ this.magFilter = magFilter !== undefined ? magFilter : NearestFilter;
+ this.minFilter = minFilter !== undefined ? minFilter : NearestFilter;
+
+ this.generateMipmaps = false;
+ this.flipY = false;
+ this.unpackAlignment = 1;
+
+}
+
+DataTexture.prototype = Object.create( Texture.prototype );
+DataTexture.prototype.constructor = DataTexture;
+
+DataTexture.prototype.isDataTexture = true;
+
+/**
+ * @author mrdoob / http://mrdoob.com/
+ */
+
+function CubeTexture( images, mapping, wrapS, wrapT, magFilter, minFilter, format, type, anisotropy, encoding ) {
+
+ images = images !== undefined ? images : [];
+ mapping = mapping !== undefined ? mapping : CubeReflectionMapping;
+
+ Texture.call( this, images, mapping, wrapS, wrapT, magFilter, minFilter, format, type, anisotropy, encoding );
+
+ this.flipY = false;
+
+}
+
+CubeTexture.prototype = Object.create( Texture.prototype );
+CubeTexture.prototype.constructor = CubeTexture;
+
+CubeTexture.prototype.isCubeTexture = true;
+
+Object.defineProperty( CubeTexture.prototype, 'images', {
+
+ get: function () {
+
+ return this.image;
+
+ },
+
+ set: function ( value ) {
+
+ this.image = value;
+
+ }
+
+} );
+
+/**
+ * @author tschw
+ *
+ * Uniforms of a program.
+ * Those form a tree structure with a special top-level container for the root,
+ * which you get by calling 'new WebGLUniforms( gl, program, renderer )'.
+ *
+ *
+ * Properties of inner nodes including the top-level container:
+ *
+ * .seq - array of nested uniforms
+ * .map - nested uniforms by name
+ *
+ *
+ * Methods of all nodes except the top-level container:
+ *
+ * .setValue( gl, value, [renderer] )
+ *
+ * uploads a uniform value(s)
+ * the 'renderer' parameter is needed for sampler uniforms
+ *
+ *
+ * Static methods of the top-level container (renderer factorizations):
+ *
+ * .upload( gl, seq, values, renderer )
+ *
+ * sets uniforms in 'seq' to 'values[id].value'
+ *
+ * .seqWithValue( seq, values ) : filteredSeq
+ *
+ * filters 'seq' entries with corresponding entry in values
+ *
+ *
+ * Methods of the top-level container (renderer factorizations):
+ *
+ * .setValue( gl, name, value )
+ *
+ * sets uniform with name 'name' to 'value'
+ *
+ * .set( gl, obj, prop )
+ *
+ * sets uniform from object and property with same name than uniform
+ *
+ * .setOptional( gl, obj, prop )
+ *
+ * like .set for an optional property of the object
+ *
+ */
+
+var emptyTexture = new Texture();
+var emptyCubeTexture = new CubeTexture();
+
+// --- Base for inner nodes (including the root) ---
+
+function UniformContainer() {
+
+ this.seq = [];
+ this.map = {};
+
+}
+
+// --- Utilities ---
+
+// Array Caches (provide typed arrays for temporary by size)
+
+var arrayCacheF32 = [];
+var arrayCacheI32 = [];
+
+// Float32Array caches used for uploading Matrix uniforms
+
+var mat4array = new Float32Array( 16 );
+var mat3array = new Float32Array( 9 );
+
+// Flattening for arrays of vectors and matrices
+
+function flatten( array, nBlocks, blockSize ) {
+
+ var firstElem = array[ 0 ];
+
+ if ( firstElem <= 0 || firstElem > 0 ) return array;
+ // unoptimized: ! isNaN( firstElem )
+ // see http://jacksondunstan.com/articles/983
+
+ var n = nBlocks * blockSize,
+ r = arrayCacheF32[ n ];
+
+ if ( r === undefined ) {
+
+ r = new Float32Array( n );
+ arrayCacheF32[ n ] = r;
+
+ }
+
+ if ( nBlocks !== 0 ) {
+
+ firstElem.toArray( r, 0 );
+
+ for ( var i = 1, offset = 0; i !== nBlocks; ++ i ) {
+
+ offset += blockSize;
+ array[ i ].toArray( r, offset );
+
+ }
+
+ }
+
+ return r;
+
+}
+
+// Texture unit allocation
+
+function allocTexUnits( renderer, n ) {
+
+ var r = arrayCacheI32[ n ];
+
+ if ( r === undefined ) {
+
+ r = new Int32Array( n );
+ arrayCacheI32[ n ] = r;
+
+ }
+
+ for ( var i = 0; i !== n; ++ i )
+ r[ i ] = renderer.allocTextureUnit();
+
+ return r;
+
+}
+
+// --- Setters ---
+
+// Note: Defining these methods externally, because they come in a bunch
+// and this way their names minify.
+
+// Single scalar
+
+function setValue1f( gl, v ) {
+
+ gl.uniform1f( this.addr, v );
+
+}
+
+function setValue1i( gl, v ) {
+
+ gl.uniform1i( this.addr, v );
+
+}
+
+// Single float vector (from flat array or THREE.VectorN)
+
+function setValue2fv( gl, v ) {
+
+ if ( v.x === undefined ) {
+
+ gl.uniform2fv( this.addr, v );
+
+ } else {
+
+ gl.uniform2f( this.addr, v.x, v.y );
+
+ }
+
+}
+
+function setValue3fv( gl, v ) {
+
+ if ( v.x !== undefined ) {
+
+ gl.uniform3f( this.addr, v.x, v.y, v.z );
+
+ } else if ( v.r !== undefined ) {
+
+ gl.uniform3f( this.addr, v.r, v.g, v.b );
+
+ } else {
+
+ gl.uniform3fv( this.addr, v );
+
+ }
+
+}
+
+function setValue4fv( gl, v ) {
+
+ if ( v.x === undefined ) {
+
+ gl.uniform4fv( this.addr, v );
+
+ } else {
+
+ gl.uniform4f( this.addr, v.x, v.y, v.z, v.w );
+
+ }
+
+}
+
+// Single matrix (from flat array or MatrixN)
+
+function setValue2fm( gl, v ) {
+
+ gl.uniformMatrix2fv( this.addr, false, v.elements || v );
+
+}
+
+function setValue3fm( gl, v ) {
+
+ if ( v.elements === undefined ) {
+
+ gl.uniformMatrix3fv( this.addr, false, v );
+
+ } else {
+
+ mat3array.set( v.elements );
+ gl.uniformMatrix3fv( this.addr, false, mat3array );
+
+ }
+
+}
+
+function setValue4fm( gl, v ) {
+
+ if ( v.elements === undefined ) {
+
+ gl.uniformMatrix4fv( this.addr, false, v );
+
+ } else {
+
+ mat4array.set( v.elements );
+ gl.uniformMatrix4fv( this.addr, false, mat4array );
+
+ }
+
+}
+
+// Single texture (2D / Cube)
+
+function setValueT1( gl, v, renderer ) {
+
+ var unit = renderer.allocTextureUnit();
+ gl.uniform1i( this.addr, unit );
+ renderer.setTexture2D( v || emptyTexture, unit );
+
+}
+
+function setValueT6( gl, v, renderer ) {
+
+ var unit = renderer.allocTextureUnit();
+ gl.uniform1i( this.addr, unit );
+ renderer.setTextureCube( v || emptyCubeTexture, unit );
+
+}
+
+// Integer / Boolean vectors or arrays thereof (always flat arrays)
+
+function setValue2iv( gl, v ) {
+
+ gl.uniform2iv( this.addr, v );
+
+}
+
+function setValue3iv( gl, v ) {
+
+ gl.uniform3iv( this.addr, v );
+
+}
+
+function setValue4iv( gl, v ) {
+
+ gl.uniform4iv( this.addr, v );
+
+}
+
+// Helper to pick the right setter for the singular case
+
+function getSingularSetter( type ) {
+
+ switch ( type ) {
+
+ case 0x1406: return setValue1f; // FLOAT
+ case 0x8b50: return setValue2fv; // _VEC2
+ case 0x8b51: return setValue3fv; // _VEC3
+ case 0x8b52: return setValue4fv; // _VEC4
+
+ case 0x8b5a: return setValue2fm; // _MAT2
+ case 0x8b5b: return setValue3fm; // _MAT3
+ case 0x8b5c: return setValue4fm; // _MAT4
+
+ case 0x8b5e: case 0x8d66: return setValueT1; // SAMPLER_2D, SAMPLER_EXTERNAL_OES
+ case 0x8b60: return setValueT6; // SAMPLER_CUBE
+
+ case 0x1404: case 0x8b56: return setValue1i; // INT, BOOL
+ case 0x8b53: case 0x8b57: return setValue2iv; // _VEC2
+ case 0x8b54: case 0x8b58: return setValue3iv; // _VEC3
+ case 0x8b55: case 0x8b59: return setValue4iv; // _VEC4
+
+ }
+
+}
+
+// Array of scalars
+
+function setValue1fv( gl, v ) {
+
+ gl.uniform1fv( this.addr, v );
+
+}
+function setValue1iv( gl, v ) {
+
+ gl.uniform1iv( this.addr, v );
+
+}
+
+// Array of vectors (flat or from THREE classes)
+
+function setValueV2a( gl, v ) {
+
+ gl.uniform2fv( this.addr, flatten( v, this.size, 2 ) );
+
+}
+
+function setValueV3a( gl, v ) {
+
+ gl.uniform3fv( this.addr, flatten( v, this.size, 3 ) );
+
+}
+
+function setValueV4a( gl, v ) {
+
+ gl.uniform4fv( this.addr, flatten( v, this.size, 4 ) );
+
+}
+
+// Array of matrices (flat or from THREE clases)
+
+function setValueM2a( gl, v ) {
+
+ gl.uniformMatrix2fv( this.addr, false, flatten( v, this.size, 4 ) );
+
+}
+
+function setValueM3a( gl, v ) {
+
+ gl.uniformMatrix3fv( this.addr, false, flatten( v, this.size, 9 ) );
+
+}
+
+function setValueM4a( gl, v ) {
+
+ gl.uniformMatrix4fv( this.addr, false, flatten( v, this.size, 16 ) );
+
+}
+
+// Array of textures (2D / Cube)
+
+function setValueT1a( gl, v, renderer ) {
+
+ var n = v.length,
+ units = allocTexUnits( renderer, n );
+
+ gl.uniform1iv( this.addr, units );
+
+ for ( var i = 0; i !== n; ++ i ) {
+
+ renderer.setTexture2D( v[ i ] || emptyTexture, units[ i ] );
+
+ }
+
+}
+
+function setValueT6a( gl, v, renderer ) {
+
+ var n = v.length,
+ units = allocTexUnits( renderer, n );
+
+ gl.uniform1iv( this.addr, units );
+
+ for ( var i = 0; i !== n; ++ i ) {
+
+ renderer.setTextureCube( v[ i ] || emptyCubeTexture, units[ i ] );
+
+ }
+
+}
+
+// Helper to pick the right setter for a pure (bottom-level) array
+
+function getPureArraySetter( type ) {
+
+ switch ( type ) {
+
+ case 0x1406: return setValue1fv; // FLOAT
+ case 0x8b50: return setValueV2a; // _VEC2
+ case 0x8b51: return setValueV3a; // _VEC3
+ case 0x8b52: return setValueV4a; // _VEC4
+
+ case 0x8b5a: return setValueM2a; // _MAT2
+ case 0x8b5b: return setValueM3a; // _MAT3
+ case 0x8b5c: return setValueM4a; // _MAT4
+
+ case 0x8b5e: return setValueT1a; // SAMPLER_2D
+ case 0x8b60: return setValueT6a; // SAMPLER_CUBE
+
+ case 0x1404: case 0x8b56: return setValue1iv; // INT, BOOL
+ case 0x8b53: case 0x8b57: return setValue2iv; // _VEC2
+ case 0x8b54: case 0x8b58: return setValue3iv; // _VEC3
+ case 0x8b55: case 0x8b59: return setValue4iv; // _VEC4
+
+ }
+
+}
+
+// --- Uniform Classes ---
+
+function SingleUniform( id, activeInfo, addr ) {
+
+ this.id = id;
+ this.addr = addr;
+ this.setValue = getSingularSetter( activeInfo.type );
+
+ // this.path = activeInfo.name; // DEBUG
+
+}
+
+function PureArrayUniform( id, activeInfo, addr ) {
+
+ this.id = id;
+ this.addr = addr;
+ this.size = activeInfo.size;
+ this.setValue = getPureArraySetter( activeInfo.type );
+
+ // this.path = activeInfo.name; // DEBUG
+
+}
+
+function StructuredUniform( id ) {
+
+ this.id = id;
+
+ UniformContainer.call( this ); // mix-in
+
+}
+
+StructuredUniform.prototype.setValue = function ( gl, value ) {
+
+ // Note: Don't need an extra 'renderer' parameter, since samplers
+ // are not allowed in structured uniforms.
+
+ var seq = this.seq;
+
+ for ( var i = 0, n = seq.length; i !== n; ++ i ) {
+
+ var u = seq[ i ];
+ u.setValue( gl, value[ u.id ] );
+
+ }
+
+};
+
+// --- Top-level ---
+
+// Parser - builds up the property tree from the path strings
+
+var RePathPart = /([\w\d_]+)(\])?(\[|\.)?/g;
+
+// extracts
+// - the identifier (member name or array index)
+// - followed by an optional right bracket (found when array index)
+// - followed by an optional left bracket or dot (type of subscript)
+//
+// Note: These portions can be read in a non-overlapping fashion and
+// allow straightforward parsing of the hierarchy that WebGL encodes
+// in the uniform names.
+
+function addUniform( container, uniformObject ) {
+
+ container.seq.push( uniformObject );
+ container.map[ uniformObject.id ] = uniformObject;
+
+}
+
+function parseUniform( activeInfo, addr, container ) {
+
+ var path = activeInfo.name,
+ pathLength = path.length;
+
+ // reset RegExp object, because of the early exit of a previous run
+ RePathPart.lastIndex = 0;
+
+ for ( ; ; ) {
+
+ var match = RePathPart.exec( path ),
+ matchEnd = RePathPart.lastIndex,
+
+ id = match[ 1 ],
+ idIsIndex = match[ 2 ] === ']',
+ subscript = match[ 3 ];
+
+ if ( idIsIndex ) id = id | 0; // convert to integer
+
+ if ( subscript === undefined || subscript === '[' && matchEnd + 2 === pathLength ) {
+
+ // bare name or "pure" bottom-level array "[0]" suffix
+
+ addUniform( container, subscript === undefined ?
+ new SingleUniform( id, activeInfo, addr ) :
+ new PureArrayUniform( id, activeInfo, addr ) );
+
+ break;
+
+ } else {
+
+ // step into inner node / create it in case it doesn't exist
+
+ var map = container.map, next = map[ id ];
+
+ if ( next === undefined ) {
+
+ next = new StructuredUniform( id );
+ addUniform( container, next );
+
+ }
+
+ container = next;
+
+ }
+
+ }
+
+}
+
+// Root Container
+
+function WebGLUniforms( gl, program, renderer ) {
+
+ UniformContainer.call( this );
+
+ this.renderer = renderer;
+
+ var n = gl.getProgramParameter( program, gl.ACTIVE_UNIFORMS );
+
+ for ( var i = 0; i < n; ++ i ) {
+
+ var info = gl.getActiveUniform( program, i ),
+ path = info.name,
+ addr = gl.getUniformLocation( program, path );
+
+ parseUniform( info, addr, this );
+
+ }
+
+}
+
+WebGLUniforms.prototype.setValue = function ( gl, name, value ) {
+
+ var u = this.map[ name ];
+
+ if ( u !== undefined ) u.setValue( gl, value, this.renderer );
+
+};
+
+WebGLUniforms.prototype.setOptional = function ( gl, object, name ) {
+
+ var v = object[ name ];
+
+ if ( v !== undefined ) this.setValue( gl, name, v );
+
+};
+
+
+// Static interface
+
+WebGLUniforms.upload = function ( gl, seq, values, renderer ) {
+
+ for ( var i = 0, n = seq.length; i !== n; ++ i ) {
+
+ var u = seq[ i ],
+ v = values[ u.id ];
+
+ if ( v.needsUpdate !== false ) {
+
+ // note: always updating when .needsUpdate is undefined
+ u.setValue( gl, v.value, renderer );
+
+ }
+
+ }
+
+};
+
+WebGLUniforms.seqWithValue = function ( seq, values ) {
+
+ var r = [];
+
+ for ( var i = 0, n = seq.length; i !== n; ++ i ) {
+
+ var u = seq[ i ];
+ if ( u.id in values ) r.push( u );
+
+ }
+
+ return r;
+
+};
+
+/**
+ * @author mrdoob / http://mrdoob.com/
+ */
+
+var ColorKeywords = { 'aliceblue': 0xF0F8FF, 'antiquewhite': 0xFAEBD7, 'aqua': 0x00FFFF, 'aquamarine': 0x7FFFD4, 'azure': 0xF0FFFF,
+ 'beige': 0xF5F5DC, 'bisque': 0xFFE4C4, 'black': 0x000000, 'blanchedalmond': 0xFFEBCD, 'blue': 0x0000FF, 'blueviolet': 0x8A2BE2,
+ 'brown': 0xA52A2A, 'burlywood': 0xDEB887, 'cadetblue': 0x5F9EA0, 'chartreuse': 0x7FFF00, 'chocolate': 0xD2691E, 'coral': 0xFF7F50,
+ 'cornflowerblue': 0x6495ED, 'cornsilk': 0xFFF8DC, 'crimson': 0xDC143C, 'cyan': 0x00FFFF, 'darkblue': 0x00008B, 'darkcyan': 0x008B8B,
+ 'darkgoldenrod': 0xB8860B, 'darkgray': 0xA9A9A9, 'darkgreen': 0x006400, 'darkgrey': 0xA9A9A9, 'darkkhaki': 0xBDB76B, 'darkmagenta': 0x8B008B,
+ 'darkolivegreen': 0x556B2F, 'darkorange': 0xFF8C00, 'darkorchid': 0x9932CC, 'darkred': 0x8B0000, 'darksalmon': 0xE9967A, 'darkseagreen': 0x8FBC8F,
+ 'darkslateblue': 0x483D8B, 'darkslategray': 0x2F4F4F, 'darkslategrey': 0x2F4F4F, 'darkturquoise': 0x00CED1, 'darkviolet': 0x9400D3,
+ 'deeppink': 0xFF1493, 'deepskyblue': 0x00BFFF, 'dimgray': 0x696969, 'dimgrey': 0x696969, 'dodgerblue': 0x1E90FF, 'firebrick': 0xB22222,
+ 'floralwhite': 0xFFFAF0, 'forestgreen': 0x228B22, 'fuchsia': 0xFF00FF, 'gainsboro': 0xDCDCDC, 'ghostwhite': 0xF8F8FF, 'gold': 0xFFD700,
+ 'goldenrod': 0xDAA520, 'gray': 0x808080, 'green': 0x008000, 'greenyellow': 0xADFF2F, 'grey': 0x808080, 'honeydew': 0xF0FFF0, 'hotpink': 0xFF69B4,
+ 'indianred': 0xCD5C5C, 'indigo': 0x4B0082, 'ivory': 0xFFFFF0, 'khaki': 0xF0E68C, 'lavender': 0xE6E6FA, 'lavenderblush': 0xFFF0F5, 'lawngreen': 0x7CFC00,
+ 'lemonchiffon': 0xFFFACD, 'lightblue': 0xADD8E6, 'lightcoral': 0xF08080, 'lightcyan': 0xE0FFFF, 'lightgoldenrodyellow': 0xFAFAD2, 'lightgray': 0xD3D3D3,
+ 'lightgreen': 0x90EE90, 'lightgrey': 0xD3D3D3, 'lightpink': 0xFFB6C1, 'lightsalmon': 0xFFA07A, 'lightseagreen': 0x20B2AA, 'lightskyblue': 0x87CEFA,
+ 'lightslategray': 0x778899, 'lightslategrey': 0x778899, 'lightsteelblue': 0xB0C4DE, 'lightyellow': 0xFFFFE0, 'lime': 0x00FF00, 'limegreen': 0x32CD32,
+ 'linen': 0xFAF0E6, 'magenta': 0xFF00FF, 'maroon': 0x800000, 'mediumaquamarine': 0x66CDAA, 'mediumblue': 0x0000CD, 'mediumorchid': 0xBA55D3,
+ 'mediumpurple': 0x9370DB, 'mediumseagreen': 0x3CB371, 'mediumslateblue': 0x7B68EE, 'mediumspringgreen': 0x00FA9A, 'mediumturquoise': 0x48D1CC,
+ 'mediumvioletred': 0xC71585, 'midnightblue': 0x191970, 'mintcream': 0xF5FFFA, 'mistyrose': 0xFFE4E1, 'moccasin': 0xFFE4B5, 'navajowhite': 0xFFDEAD,
+ 'navy': 0x000080, 'oldlace': 0xFDF5E6, 'olive': 0x808000, 'olivedrab': 0x6B8E23, 'orange': 0xFFA500, 'orangered': 0xFF4500, 'orchid': 0xDA70D6,
+ 'palegoldenrod': 0xEEE8AA, 'palegreen': 0x98FB98, 'paleturquoise': 0xAFEEEE, 'palevioletred': 0xDB7093, 'papayawhip': 0xFFEFD5, 'peachpuff': 0xFFDAB9,
+ 'peru': 0xCD853F, 'pink': 0xFFC0CB, 'plum': 0xDDA0DD, 'powderblue': 0xB0E0E6, 'purple': 0x800080, 'rebeccapurple': 0x663399, 'red': 0xFF0000, 'rosybrown': 0xBC8F8F,
+ 'royalblue': 0x4169E1, 'saddlebrown': 0x8B4513, 'salmon': 0xFA8072, 'sandybrown': 0xF4A460, 'seagreen': 0x2E8B57, 'seashell': 0xFFF5EE,
+ 'sienna': 0xA0522D, 'silver': 0xC0C0C0, 'skyblue': 0x87CEEB, 'slateblue': 0x6A5ACD, 'slategray': 0x708090, 'slategrey': 0x708090, 'snow': 0xFFFAFA,
+ 'springgreen': 0x00FF7F, 'steelblue': 0x4682B4, 'tan': 0xD2B48C, 'teal': 0x008080, 'thistle': 0xD8BFD8, 'tomato': 0xFF6347, 'turquoise': 0x40E0D0,
+ 'violet': 0xEE82EE, 'wheat': 0xF5DEB3, 'white': 0xFFFFFF, 'whitesmoke': 0xF5F5F5, 'yellow': 0xFFFF00, 'yellowgreen': 0x9ACD32 };
+
+function Color( r, g, b ) {
+
+ if ( g === undefined && b === undefined ) {
+
+ // r is THREE.Color, hex or string
+ return this.set( r );
+
+ }
+
+ return this.setRGB( r, g, b );
+
+}
+
+Object.assign( Color.prototype, {
+
+ isColor: true,
+
+ r: 1, g: 1, b: 1,
+
+ set: function ( value ) {
+
+ if ( value && value.isColor ) {
+
+ this.copy( value );
+
+ } else if ( typeof value === 'number' ) {
+
+ this.setHex( value );
+
+ } else if ( typeof value === 'string' ) {
+
+ this.setStyle( value );
+
+ }
+
+ return this;
+
+ },
+
+ setScalar: function ( scalar ) {
+
+ this.r = scalar;
+ this.g = scalar;
+ this.b = scalar;
+
+ return this;
+
+ },
+
+ setHex: function ( hex ) {
+
+ hex = Math.floor( hex );
+
+ this.r = ( hex >> 16 & 255 ) / 255;
+ this.g = ( hex >> 8 & 255 ) / 255;
+ this.b = ( hex & 255 ) / 255;
+
+ return this;
+
+ },
+
+ setRGB: function ( r, g, b ) {
+
+ this.r = r;
+ this.g = g;
+ this.b = b;
+
+ return this;
+
+ },
+
+ setHSL: function () {
+
+ function hue2rgb( p, q, t ) {
+
+ if ( t < 0 ) t += 1;
+ if ( t > 1 ) t -= 1;
+ if ( t < 1 / 6 ) return p + ( q - p ) * 6 * t;
+ if ( t < 1 / 2 ) return q;
+ if ( t < 2 / 3 ) return p + ( q - p ) * 6 * ( 2 / 3 - t );
+ return p;
+
+ }
+
+ return function setHSL( h, s, l ) {
+
+ // h,s,l ranges are in 0.0 - 1.0
+ h = _Math.euclideanModulo( h, 1 );
+ s = _Math.clamp( s, 0, 1 );
+ l = _Math.clamp( l, 0, 1 );
+
+ if ( s === 0 ) {
+
+ this.r = this.g = this.b = l;
+
+ } else {
+
+ var p = l <= 0.5 ? l * ( 1 + s ) : l + s - ( l * s );
+ var q = ( 2 * l ) - p;
+
+ this.r = hue2rgb( q, p, h + 1 / 3 );
+ this.g = hue2rgb( q, p, h );
+ this.b = hue2rgb( q, p, h - 1 / 3 );
+
+ }
+
+ return this;
+
+ };
+
+ }(),
+
+ setStyle: function ( style ) {
+
+ function handleAlpha( string ) {
+
+ if ( string === undefined ) return;
+
+ if ( parseFloat( string ) < 1 ) {
+
+ console.warn( 'THREE.Color: Alpha component of ' + style + ' will be ignored.' );
+
+ }
+
+ }
+
+
+ var m;
+
+ if ( m = /^((?:rgb|hsl)a?)\(\s*([^\)]*)\)/.exec( style ) ) {
+
+ // rgb / hsl
+
+ var color;
+ var name = m[ 1 ];
+ var components = m[ 2 ];
+
+ switch ( name ) {
+
+ case 'rgb':
+ case 'rgba':
+
+ if ( color = /^(\d+)\s*,\s*(\d+)\s*,\s*(\d+)\s*(,\s*([0-9]*\.?[0-9]+)\s*)?$/.exec( components ) ) {
+
+ // rgb(255,0,0) rgba(255,0,0,0.5)
+ this.r = Math.min( 255, parseInt( color[ 1 ], 10 ) ) / 255;
+ this.g = Math.min( 255, parseInt( color[ 2 ], 10 ) ) / 255;
+ this.b = Math.min( 255, parseInt( color[ 3 ], 10 ) ) / 255;
+
+ handleAlpha( color[ 5 ] );
+
+ return this;
+
+ }
+
+ if ( color = /^(\d+)\%\s*,\s*(\d+)\%\s*,\s*(\d+)\%\s*(,\s*([0-9]*\.?[0-9]+)\s*)?$/.exec( components ) ) {
+
+ // rgb(100%,0%,0%) rgba(100%,0%,0%,0.5)
+ this.r = Math.min( 100, parseInt( color[ 1 ], 10 ) ) / 100;
+ this.g = Math.min( 100, parseInt( color[ 2 ], 10 ) ) / 100;
+ this.b = Math.min( 100, parseInt( color[ 3 ], 10 ) ) / 100;
+
+ handleAlpha( color[ 5 ] );
+
+ return this;
+
+ }
+
+ break;
+
+ case 'hsl':
+ case 'hsla':
+
+ if ( color = /^([0-9]*\.?[0-9]+)\s*,\s*(\d+)\%\s*,\s*(\d+)\%\s*(,\s*([0-9]*\.?[0-9]+)\s*)?$/.exec( components ) ) {
+
+ // hsl(120,50%,50%) hsla(120,50%,50%,0.5)
+ var h = parseFloat( color[ 1 ] ) / 360;
+ var s = parseInt( color[ 2 ], 10 ) / 100;
+ var l = parseInt( color[ 3 ], 10 ) / 100;
+
+ handleAlpha( color[ 5 ] );
+
+ return this.setHSL( h, s, l );
+
+ }
+
+ break;
+
+ }
+
+ } else if ( m = /^\#([A-Fa-f0-9]+)$/.exec( style ) ) {
+
+ // hex color
+
+ var hex = m[ 1 ];
+ var size = hex.length;
+
+ if ( size === 3 ) {
+
+ // #ff0
+ this.r = parseInt( hex.charAt( 0 ) + hex.charAt( 0 ), 16 ) / 255;
+ this.g = parseInt( hex.charAt( 1 ) + hex.charAt( 1 ), 16 ) / 255;
+ this.b = parseInt( hex.charAt( 2 ) + hex.charAt( 2 ), 16 ) / 255;
+
+ return this;
+
+ } else if ( size === 6 ) {
+
+ // #ff0000
+ this.r = parseInt( hex.charAt( 0 ) + hex.charAt( 1 ), 16 ) / 255;
+ this.g = parseInt( hex.charAt( 2 ) + hex.charAt( 3 ), 16 ) / 255;
+ this.b = parseInt( hex.charAt( 4 ) + hex.charAt( 5 ), 16 ) / 255;
+
+ return this;
+
+ }
+
+ }
+
+ if ( style && style.length > 0 ) {
+
+ // color keywords
+ var hex = ColorKeywords[ style ];
+
+ if ( hex !== undefined ) {
+
+ // red
+ this.setHex( hex );
+
+ } else {
+
+ // unknown color
+ console.warn( 'THREE.Color: Unknown color ' + style );
+
+ }
+
+ }
+
+ return this;
+
+ },
+
+ clone: function () {
+
+ return new this.constructor( this.r, this.g, this.b );
+
+ },
+
+ copy: function ( color ) {
+
+ this.r = color.r;
+ this.g = color.g;
+ this.b = color.b;
+
+ return this;
+
+ },
+
+ copyGammaToLinear: function ( color, gammaFactor ) {
+
+ if ( gammaFactor === undefined ) gammaFactor = 2.0;
+
+ this.r = Math.pow( color.r, gammaFactor );
+ this.g = Math.pow( color.g, gammaFactor );
+ this.b = Math.pow( color.b, gammaFactor );
+
+ return this;
+
+ },
+
+ copyLinearToGamma: function ( color, gammaFactor ) {
+
+ if ( gammaFactor === undefined ) gammaFactor = 2.0;
+
+ var safeInverse = ( gammaFactor > 0 ) ? ( 1.0 / gammaFactor ) : 1.0;
+
+ this.r = Math.pow( color.r, safeInverse );
+ this.g = Math.pow( color.g, safeInverse );
+ this.b = Math.pow( color.b, safeInverse );
+
+ return this;
+
+ },
+
+ convertGammaToLinear: function () {
+
+ var r = this.r, g = this.g, b = this.b;
+
+ this.r = r * r;
+ this.g = g * g;
+ this.b = b * b;
+
+ return this;
+
+ },
+
+ convertLinearToGamma: function () {
+
+ this.r = Math.sqrt( this.r );
+ this.g = Math.sqrt( this.g );
+ this.b = Math.sqrt( this.b );
+
+ return this;
+
+ },
+
+ getHex: function () {
+
+ return ( this.r * 255 ) << 16 ^ ( this.g * 255 ) << 8 ^ ( this.b * 255 ) << 0;
+
+ },
+
+ getHexString: function () {
+
+ return ( '000000' + this.getHex().toString( 16 ) ).slice( - 6 );
+
+ },
+
+ getHSL: function ( optionalTarget ) {
+
+ // h,s,l ranges are in 0.0 - 1.0
+
+ var hsl = optionalTarget || { h: 0, s: 0, l: 0 };
+
+ var r = this.r, g = this.g, b = this.b;
+
+ var max = Math.max( r, g, b );
+ var min = Math.min( r, g, b );
+
+ var hue, saturation;
+ var lightness = ( min + max ) / 2.0;
+
+ if ( min === max ) {
+
+ hue = 0;
+ saturation = 0;
+
+ } else {
+
+ var delta = max - min;
+
+ saturation = lightness <= 0.5 ? delta / ( max + min ) : delta / ( 2 - max - min );
+
+ switch ( max ) {
+
+ case r: hue = ( g - b ) / delta + ( g < b ? 6 : 0 ); break;
+ case g: hue = ( b - r ) / delta + 2; break;
+ case b: hue = ( r - g ) / delta + 4; break;
+
+ }
+
+ hue /= 6;
+
+ }
+
+ hsl.h = hue;
+ hsl.s = saturation;
+ hsl.l = lightness;
+
+ return hsl;
+
+ },
+
+ getStyle: function () {
+
+ return 'rgb(' + ( ( this.r * 255 ) | 0 ) + ',' + ( ( this.g * 255 ) | 0 ) + ',' + ( ( this.b * 255 ) | 0 ) + ')';
+
+ },
+
+ offsetHSL: function ( h, s, l ) {
+
+ var hsl = this.getHSL();
+
+ hsl.h += h; hsl.s += s; hsl.l += l;
+
+ this.setHSL( hsl.h, hsl.s, hsl.l );
+
+ return this;
+
+ },
+
+ add: function ( color ) {
+
+ this.r += color.r;
+ this.g += color.g;
+ this.b += color.b;
+
+ return this;
+
+ },
+
+ addColors: function ( color1, color2 ) {
+
+ this.r = color1.r + color2.r;
+ this.g = color1.g + color2.g;
+ this.b = color1.b + color2.b;
+
+ return this;
+
+ },
+
+ addScalar: function ( s ) {
+
+ this.r += s;
+ this.g += s;
+ this.b += s;
+
+ return this;
+
+ },
+
+ sub: function ( color ) {
+
+ this.r = Math.max( 0, this.r - color.r );
+ this.g = Math.max( 0, this.g - color.g );
+ this.b = Math.max( 0, this.b - color.b );
+
+ return this;
+
+ },
+
+ multiply: function ( color ) {
+
+ this.r *= color.r;
+ this.g *= color.g;
+ this.b *= color.b;
+
+ return this;
+
+ },
+
+ multiplyScalar: function ( s ) {
+
+ this.r *= s;
+ this.g *= s;
+ this.b *= s;
+
+ return this;
+
+ },
+
+ lerp: function ( color, alpha ) {
+
+ this.r += ( color.r - this.r ) * alpha;
+ this.g += ( color.g - this.g ) * alpha;
+ this.b += ( color.b - this.b ) * alpha;
+
+ return this;
+
+ },
+
+ equals: function ( c ) {
+
+ return ( c.r === this.r ) && ( c.g === this.g ) && ( c.b === this.b );
+
+ },
+
+ fromArray: function ( array, offset ) {
+
+ if ( offset === undefined ) offset = 0;
+
+ this.r = array[ offset ];
+ this.g = array[ offset + 1 ];
+ this.b = array[ offset + 2 ];
+
+ return this;
+
+ },
+
+ toArray: function ( array, offset ) {
+
+ if ( array === undefined ) array = [];
+ if ( offset === undefined ) offset = 0;
+
+ array[ offset ] = this.r;
+ array[ offset + 1 ] = this.g;
+ array[ offset + 2 ] = this.b;
+
+ return array;
+
+ },
+
+ toJSON: function () {
+
+ return this.getHex();
+
+ }
+
+} );
+
+/**
+ * Uniforms library for shared webgl shaders
+ */
+
+var UniformsLib = {
+
+ common: {
+
+ diffuse: { value: new Color( 0xeeeeee ) },
+ opacity: { value: 1.0 },
+
+ map: { value: null },
+ uvTransform: { value: new Matrix3() },
+
+ alphaMap: { value: null },
+
+ },
+
+ specularmap: {
+
+ specularMap: { value: null },
+
+ },
+
+ envmap: {
+
+ envMap: { value: null },
+ flipEnvMap: { value: - 1 },
+ reflectivity: { value: 1.0 },
+ refractionRatio: { value: 0.98 }
+
+ },
+
+ aomap: {
+
+ aoMap: { value: null },
+ aoMapIntensity: { value: 1 }
+
+ },
+
+ lightmap: {
+
+ lightMap: { value: null },
+ lightMapIntensity: { value: 1 }
+
+ },
+
+ emissivemap: {
+
+ emissiveMap: { value: null }
+
+ },
+
+ bumpmap: {
+
+ bumpMap: { value: null },
+ bumpScale: { value: 1 }
+
+ },
+
+ normalmap: {
+
+ normalMap: { value: null },
+ normalScale: { value: new Vector2( 1, 1 ) }
+
+ },
+
+ displacementmap: {
+
+ displacementMap: { value: null },
+ displacementScale: { value: 1 },
+ displacementBias: { value: 0 }
+
+ },
+
+ roughnessmap: {
+
+ roughnessMap: { value: null }
+
+ },
+
+ metalnessmap: {
+
+ metalnessMap: { value: null }
+
+ },
+
+ gradientmap: {
+
+ gradientMap: { value: null }
+
+ },
+
+ fog: {
+
+ fogDensity: { value: 0.00025 },
+ fogNear: { value: 1 },
+ fogFar: { value: 2000 },
+ fogColor: { value: new Color( 0xffffff ) }
+
+ },
+
+ lights: {
+
+ ambientLightColor: { value: [] },
+
+ directionalLights: { value: [], properties: {
+ direction: {},
+ color: {},
+
+ shadow: {},
+ shadowBias: {},
+ shadowRadius: {},
+ shadowMapSize: {}
+ } },
+
+ directionalShadowMap: { value: [] },
+ directionalShadowMatrix: { value: [] },
+
+ spotLights: { value: [], properties: {
+ color: {},
+ position: {},
+ direction: {},
+ distance: {},
+ coneCos: {},
+ penumbraCos: {},
+ decay: {},
+
+ shadow: {},
+ shadowBias: {},
+ shadowRadius: {},
+ shadowMapSize: {}
+ } },
+
+ spotShadowMap: { value: [] },
+ spotShadowMatrix: { value: [] },
+
+ pointLights: { value: [], properties: {
+ color: {},
+ position: {},
+ decay: {},
+ distance: {},
+
+ shadow: {},
+ shadowBias: {},
+ shadowRadius: {},
+ shadowMapSize: {},
+ shadowCameraNear: {},
+ shadowCameraFar: {}
+ } },
+
+ pointShadowMap: { value: [] },
+ pointShadowMatrix: { value: [] },
+
+ hemisphereLights: { value: [], properties: {
+ direction: {},
+ skyColor: {},
+ groundColor: {}
+ } },
+
+ // TODO (abelnation): RectAreaLight BRDF data needs to be moved from example to main src
+ rectAreaLights: { value: [], properties: {
+ color: {},
+ position: {},
+ width: {},
+ height: {}
+ } }
+
+ },
+
+ points: {
+
+ diffuse: { value: new Color( 0xeeeeee ) },
+ opacity: { value: 1.0 },
+ size: { value: 1.0 },
+ scale: { value: 1.0 },
+ map: { value: null },
+ uvTransform: { value: new Matrix3() }
+
+ }
+
+};
+
+/**
+ * Uniform Utilities
+ */
+
+var UniformsUtils = {
+
+ merge: function ( uniforms ) {
+
+ var merged = {};
+
+ for ( var u = 0; u < uniforms.length; u ++ ) {
+
+ var tmp = this.clone( uniforms[ u ] );
+
+ for ( var p in tmp ) {
+
+ merged[ p ] = tmp[ p ];
+
+ }
+
+ }
+
+ return merged;
+
+ },
+
+ clone: function ( uniforms_src ) {
+
+ var uniforms_dst = {};
+
+ for ( var u in uniforms_src ) {
+
+ uniforms_dst[ u ] = {};
+
+ for ( var p in uniforms_src[ u ] ) {
+
+ var parameter_src = uniforms_src[ u ][ p ];
+
+ if ( parameter_src && ( parameter_src.isColor ||
+ parameter_src.isMatrix3 || parameter_src.isMatrix4 ||
+ parameter_src.isVector2 || parameter_src.isVector3 || parameter_src.isVector4 ||
+ parameter_src.isTexture ) ) {
+
+ uniforms_dst[ u ][ p ] = parameter_src.clone();
+
+ } else if ( Array.isArray( parameter_src ) ) {
+
+ uniforms_dst[ u ][ p ] = parameter_src.slice();
+
+ } else {
+
+ uniforms_dst[ u ][ p ] = parameter_src;
+
+ }
+
+ }
+
+ }
+
+ return uniforms_dst;
+
+ }
+
+};
+
+var alphamap_fragment = "#ifdef USE_ALPHAMAP\n\tdiffuseColor.a *= texture2D( alphaMap, vUv ).g;\n#endif\n";
+
+var alphamap_pars_fragment = "#ifdef USE_ALPHAMAP\n\tuniform sampler2D alphaMap;\n#endif\n";
+
+var alphatest_fragment = "#ifdef ALPHATEST\n\tif ( diffuseColor.a < ALPHATEST ) discard;\n#endif\n";
+
+var aomap_fragment = "#ifdef USE_AOMAP\n\tfloat ambientOcclusion = ( texture2D( aoMap, vUv2 ).r - 1.0 ) * aoMapIntensity + 1.0;\n\treflectedLight.indirectDiffuse *= ambientOcclusion;\n\t#if defined( USE_ENVMAP ) && defined( PHYSICAL )\n\t\tfloat dotNV = saturate( dot( geometry.normal, geometry.viewDir ) );\n\t\treflectedLight.indirectSpecular *= computeSpecularOcclusion( dotNV, ambientOcclusion, material.specularRoughness );\n\t#endif\n#endif\n";
+
+var aomap_pars_fragment = "#ifdef USE_AOMAP\n\tuniform sampler2D aoMap;\n\tuniform float aoMapIntensity;\n#endif";
+
+var begin_vertex = "\nvec3 transformed = vec3( position );\n";
+
+var beginnormal_vertex = "\nvec3 objectNormal = vec3( normal );\n";
+
+var bsdfs = "float punctualLightIntensityToIrradianceFactor( const in float lightDistance, const in float cutoffDistance, const in float decayExponent ) {\n\tif( decayExponent > 0.0 ) {\n#if defined ( PHYSICALLY_CORRECT_LIGHTS )\n\t\tfloat distanceFalloff = 1.0 / max( pow( lightDistance, decayExponent ), 0.01 );\n\t\tfloat maxDistanceCutoffFactor = pow2( saturate( 1.0 - pow4( lightDistance / cutoffDistance ) ) );\n\t\treturn distanceFalloff * maxDistanceCutoffFactor;\n#else\n\t\treturn pow( saturate( -lightDistance / cutoffDistance + 1.0 ), decayExponent );\n#endif\n\t}\n\treturn 1.0;\n}\nvec3 BRDF_Diffuse_Lambert( const in vec3 diffuseColor ) {\n\treturn RECIPROCAL_PI * diffuseColor;\n}\nvec3 F_Schlick( const in vec3 specularColor, const in float dotLH ) {\n\tfloat fresnel = exp2( ( -5.55473 * dotLH - 6.98316 ) * dotLH );\n\treturn ( 1.0 - specularColor ) * fresnel + specularColor;\n}\nfloat G_GGX_Smith( const in float alpha, const in float dotNL, const in float dotNV ) {\n\tfloat a2 = pow2( alpha );\n\tfloat gl = dotNL + sqrt( a2 + ( 1.0 - a2 ) * pow2( dotNL ) );\n\tfloat gv = dotNV + sqrt( a2 + ( 1.0 - a2 ) * pow2( dotNV ) );\n\treturn 1.0 / ( gl * gv );\n}\nfloat G_GGX_SmithCorrelated( const in float alpha, const in float dotNL, const in float dotNV ) {\n\tfloat a2 = pow2( alpha );\n\tfloat gv = dotNL * sqrt( a2 + ( 1.0 - a2 ) * pow2( dotNV ) );\n\tfloat gl = dotNV * sqrt( a2 + ( 1.0 - a2 ) * pow2( dotNL ) );\n\treturn 0.5 / max( gv + gl, EPSILON );\n}\nfloat D_GGX( const in float alpha, const in float dotNH ) {\n\tfloat a2 = pow2( alpha );\n\tfloat denom = pow2( dotNH ) * ( a2 - 1.0 ) + 1.0;\n\treturn RECIPROCAL_PI * a2 / pow2( denom );\n}\nvec3 BRDF_Specular_GGX( const in IncidentLight incidentLight, const in GeometricContext geometry, const in vec3 specularColor, const in float roughness ) {\n\tfloat alpha = pow2( roughness );\n\tvec3 halfDir = normalize( incidentLight.direction + geometry.viewDir );\n\tfloat dotNL = saturate( dot( geometry.normal, incidentLight.direction ) );\n\tfloat dotNV = saturate( dot( geometry.normal, geometry.viewDir ) );\n\tfloat dotNH = saturate( dot( geometry.normal, halfDir ) );\n\tfloat dotLH = saturate( dot( incidentLight.direction, halfDir ) );\n\tvec3 F = F_Schlick( specularColor, dotLH );\n\tfloat G = G_GGX_SmithCorrelated( alpha, dotNL, dotNV );\n\tfloat D = D_GGX( alpha, dotNH );\n\treturn F * ( G * D );\n}\nvec2 LTC_Uv( const in vec3 N, const in vec3 V, const in float roughness ) {\n\tconst float LUT_SIZE = 64.0;\n\tconst float LUT_SCALE = ( LUT_SIZE - 1.0 ) / LUT_SIZE;\n\tconst float LUT_BIAS = 0.5 / LUT_SIZE;\n\tfloat theta = acos( dot( N, V ) );\n\tvec2 uv = vec2(\n\t\tsqrt( saturate( roughness ) ),\n\t\tsaturate( theta / ( 0.5 * PI ) ) );\n\tuv = uv * LUT_SCALE + LUT_BIAS;\n\treturn uv;\n}\nfloat LTC_ClippedSphereFormFactor( const in vec3 f ) {\n\tfloat l = length( f );\n\treturn max( ( l * l + f.z ) / ( l + 1.0 ), 0.0 );\n}\nvec3 LTC_EdgeVectorFormFactor( const in vec3 v1, const in vec3 v2 ) {\n\tfloat x = dot( v1, v2 );\n\tfloat y = abs( x );\n\tfloat a = 0.86267 + (0.49788 + 0.01436 * y ) * y;\n\tfloat b = 3.45068 + (4.18814 + y) * y;\n\tfloat v = a / b;\n\tfloat theta_sintheta = (x > 0.0) ? v : 0.5 * inversesqrt( 1.0 - x * x ) - v;\n\treturn cross( v1, v2 ) * theta_sintheta;\n}\nvec3 LTC_Evaluate( const in vec3 N, const in vec3 V, const in vec3 P, const in mat3 mInv, const in vec3 rectCoords[ 4 ] ) {\n\tvec3 v1 = rectCoords[ 1 ] - rectCoords[ 0 ];\n\tvec3 v2 = rectCoords[ 3 ] - rectCoords[ 0 ];\n\tvec3 lightNormal = cross( v1, v2 );\n\tif( dot( lightNormal, P - rectCoords[ 0 ] ) < 0.0 ) return vec3( 0.0 );\n\tvec3 T1, T2;\n\tT1 = normalize( V - N * dot( V, N ) );\n\tT2 = - cross( N, T1 );\n\tmat3 mat = mInv * transposeMat3( mat3( T1, T2, N ) );\n\tvec3 coords[ 4 ];\n\tcoords[ 0 ] = mat * ( rectCoords[ 0 ] - P );\n\tcoords[ 1 ] = mat * ( rectCoords[ 1 ] - P );\n\tcoords[ 2 ] = mat * ( rectCoords[ 2 ] - P );\n\tcoords[ 3 ] = mat * ( rectCoords[ 3 ] - P );\n\tcoords[ 0 ] = normalize( coords[ 0 ] );\n\tcoords[ 1 ] = normalize( coords[ 1 ] );\n\tcoords[ 2 ] = normalize( coords[ 2 ] );\n\tcoords[ 3 ] = normalize( coords[ 3 ] );\n\tvec3 vectorFormFactor = vec3( 0.0 );\n\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 0 ], coords[ 1 ] );\n\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 1 ], coords[ 2 ] );\n\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 2 ], coords[ 3 ] );\n\tvectorFormFactor += LTC_EdgeVectorFormFactor( coords[ 3 ], coords[ 0 ] );\n\tvec3 result = vec3( LTC_ClippedSphereFormFactor( vectorFormFactor ) );\n\treturn result;\n}\nvec3 BRDF_Specular_GGX_Environment( const in GeometricContext geometry, const in vec3 specularColor, const in float roughness ) {\n\tfloat dotNV = saturate( dot( geometry.normal, geometry.viewDir ) );\n\tconst vec4 c0 = vec4( - 1, - 0.0275, - 0.572, 0.022 );\n\tconst vec4 c1 = vec4( 1, 0.0425, 1.04, - 0.04 );\n\tvec4 r = roughness * c0 + c1;\n\tfloat a004 = min( r.x * r.x, exp2( - 9.28 * dotNV ) ) * r.x + r.y;\n\tvec2 AB = vec2( -1.04, 1.04 ) * a004 + r.zw;\n\treturn specularColor * AB.x + AB.y;\n}\nfloat G_BlinnPhong_Implicit( ) {\n\treturn 0.25;\n}\nfloat D_BlinnPhong( const in float shininess, const in float dotNH ) {\n\treturn RECIPROCAL_PI * ( shininess * 0.5 + 1.0 ) * pow( dotNH, shininess );\n}\nvec3 BRDF_Specular_BlinnPhong( const in IncidentLight incidentLight, const in GeometricContext geometry, const in vec3 specularColor, const in float shininess ) {\n\tvec3 halfDir = normalize( incidentLight.direction + geometry.viewDir );\n\tfloat dotNH = saturate( dot( geometry.normal, halfDir ) );\n\tfloat dotLH = saturate( dot( incidentLight.direction, halfDir ) );\n\tvec3 F = F_Schlick( specularColor, dotLH );\n\tfloat G = G_BlinnPhong_Implicit( );\n\tfloat D = D_BlinnPhong( shininess, dotNH );\n\treturn F * ( G * D );\n}\nfloat GGXRoughnessToBlinnExponent( const in float ggxRoughness ) {\n\treturn ( 2.0 / pow2( ggxRoughness + 0.0001 ) - 2.0 );\n}\nfloat BlinnExponentToGGXRoughness( const in float blinnExponent ) {\n\treturn sqrt( 2.0 / ( blinnExponent + 2.0 ) );\n}\n";
+
+var bumpmap_pars_fragment = "#ifdef USE_BUMPMAP\n\tuniform sampler2D bumpMap;\n\tuniform float bumpScale;\n\tvec2 dHdxy_fwd() {\n\t\tvec2 dSTdx = dFdx( vUv );\n\t\tvec2 dSTdy = dFdy( vUv );\n\t\tfloat Hll = bumpScale * texture2D( bumpMap, vUv ).x;\n\t\tfloat dBx = bumpScale * texture2D( bumpMap, vUv + dSTdx ).x - Hll;\n\t\tfloat dBy = bumpScale * texture2D( bumpMap, vUv + dSTdy ).x - Hll;\n\t\treturn vec2( dBx, dBy );\n\t}\n\tvec3 perturbNormalArb( vec3 surf_pos, vec3 surf_norm, vec2 dHdxy ) {\n\t\tvec3 vSigmaX = vec3( dFdx( surf_pos.x ), dFdx( surf_pos.y ), dFdx( surf_pos.z ) );\n\t\tvec3 vSigmaY = vec3( dFdy( surf_pos.x ), dFdy( surf_pos.y ), dFdy( surf_pos.z ) );\n\t\tvec3 vN = surf_norm;\n\t\tvec3 R1 = cross( vSigmaY, vN );\n\t\tvec3 R2 = cross( vN, vSigmaX );\n\t\tfloat fDet = dot( vSigmaX, R1 );\n\t\tvec3 vGrad = sign( fDet ) * ( dHdxy.x * R1 + dHdxy.y * R2 );\n\t\treturn normalize( abs( fDet ) * surf_norm - vGrad );\n\t}\n#endif\n";
+
+var clipping_planes_fragment = "#if NUM_CLIPPING_PLANES > 0\n\tfor ( int i = 0; i < UNION_CLIPPING_PLANES; ++ i ) {\n\t\tvec4 plane = clippingPlanes[ i ];\n\t\tif ( dot( vViewPosition, plane.xyz ) > plane.w ) discard;\n\t}\n\t\t\n\t#if UNION_CLIPPING_PLANES < NUM_CLIPPING_PLANES\n\t\tbool clipped = true;\n\t\tfor ( int i = UNION_CLIPPING_PLANES; i < NUM_CLIPPING_PLANES; ++ i ) {\n\t\t\tvec4 plane = clippingPlanes[ i ];\n\t\t\tclipped = ( dot( vViewPosition, plane.xyz ) > plane.w ) && clipped;\n\t\t}\n\t\tif ( clipped ) discard;\n\t\n\t#endif\n#endif\n";
+
+var clipping_planes_pars_fragment = "#if NUM_CLIPPING_PLANES > 0\n\t#if ! defined( PHYSICAL ) && ! defined( PHONG )\n\t\tvarying vec3 vViewPosition;\n\t#endif\n\tuniform vec4 clippingPlanes[ NUM_CLIPPING_PLANES ];\n#endif\n";
+
+var clipping_planes_pars_vertex = "#if NUM_CLIPPING_PLANES > 0 && ! defined( PHYSICAL ) && ! defined( PHONG )\n\tvarying vec3 vViewPosition;\n#endif\n";
+
+var clipping_planes_vertex = "#if NUM_CLIPPING_PLANES > 0 && ! defined( PHYSICAL ) && ! defined( PHONG )\n\tvViewPosition = - mvPosition.xyz;\n#endif\n";
+
+var color_fragment = "#ifdef USE_COLOR\n\tdiffuseColor.rgb *= vColor;\n#endif";
+
+var color_pars_fragment = "#ifdef USE_COLOR\n\tvarying vec3 vColor;\n#endif\n";
+
+var color_pars_vertex = "#ifdef USE_COLOR\n\tvarying vec3 vColor;\n#endif";
+
+var color_vertex = "#ifdef USE_COLOR\n\tvColor.xyz = color.xyz;\n#endif";
+
+var common = "#define PI 3.14159265359\n#define PI2 6.28318530718\n#define PI_HALF 1.5707963267949\n#define RECIPROCAL_PI 0.31830988618\n#define RECIPROCAL_PI2 0.15915494\n#define LOG2 1.442695\n#define EPSILON 1e-6\n#define saturate(a) clamp( a, 0.0, 1.0 )\n#define whiteCompliment(a) ( 1.0 - saturate( a ) )\nfloat pow2( const in float x ) { return x*x; }\nfloat pow3( const in float x ) { return x*x*x; }\nfloat pow4( const in float x ) { float x2 = x*x; return x2*x2; }\nfloat average( const in vec3 color ) { return dot( color, vec3( 0.3333 ) ); }\nhighp float rand( const in vec2 uv ) {\n\tconst highp float a = 12.9898, b = 78.233, c = 43758.5453;\n\thighp float dt = dot( uv.xy, vec2( a,b ) ), sn = mod( dt, PI );\n\treturn fract(sin(sn) * c);\n}\nstruct IncidentLight {\n\tvec3 color;\n\tvec3 direction;\n\tbool visible;\n};\nstruct ReflectedLight {\n\tvec3 directDiffuse;\n\tvec3 directSpecular;\n\tvec3 indirectDiffuse;\n\tvec3 indirectSpecular;\n};\nstruct GeometricContext {\n\tvec3 position;\n\tvec3 normal;\n\tvec3 viewDir;\n};\nvec3 transformDirection( in vec3 dir, in mat4 matrix ) {\n\treturn normalize( ( matrix * vec4( dir, 0.0 ) ).xyz );\n}\nvec3 inverseTransformDirection( in vec3 dir, in mat4 matrix ) {\n\treturn normalize( ( vec4( dir, 0.0 ) * matrix ).xyz );\n}\nvec3 projectOnPlane(in vec3 point, in vec3 pointOnPlane, in vec3 planeNormal ) {\n\tfloat distance = dot( planeNormal, point - pointOnPlane );\n\treturn - distance * planeNormal + point;\n}\nfloat sideOfPlane( in vec3 point, in vec3 pointOnPlane, in vec3 planeNormal ) {\n\treturn sign( dot( point - pointOnPlane, planeNormal ) );\n}\nvec3 linePlaneIntersect( in vec3 pointOnLine, in vec3 lineDirection, in vec3 pointOnPlane, in vec3 planeNormal ) {\n\treturn lineDirection * ( dot( planeNormal, pointOnPlane - pointOnLine ) / dot( planeNormal, lineDirection ) ) + pointOnLine;\n}\nmat3 transposeMat3( const in mat3 m ) {\n\tmat3 tmp;\n\ttmp[ 0 ] = vec3( m[ 0 ].x, m[ 1 ].x, m[ 2 ].x );\n\ttmp[ 1 ] = vec3( m[ 0 ].y, m[ 1 ].y, m[ 2 ].y );\n\ttmp[ 2 ] = vec3( m[ 0 ].z, m[ 1 ].z, m[ 2 ].z );\n\treturn tmp;\n}\nfloat linearToRelativeLuminance( const in vec3 color ) {\n\tvec3 weights = vec3( 0.2126, 0.7152, 0.0722 );\n\treturn dot( weights, color.rgb );\n}\n";
+
+var cube_uv_reflection_fragment = "#ifdef ENVMAP_TYPE_CUBE_UV\n#define cubeUV_textureSize (1024.0)\nint getFaceFromDirection(vec3 direction) {\n\tvec3 absDirection = abs(direction);\n\tint face = -1;\n\tif( absDirection.x > absDirection.z ) {\n\t\tif(absDirection.x > absDirection.y )\n\t\t\tface = direction.x > 0.0 ? 0 : 3;\n\t\telse\n\t\t\tface = direction.y > 0.0 ? 1 : 4;\n\t}\n\telse {\n\t\tif(absDirection.z > absDirection.y )\n\t\t\tface = direction.z > 0.0 ? 2 : 5;\n\t\telse\n\t\t\tface = direction.y > 0.0 ? 1 : 4;\n\t}\n\treturn face;\n}\n#define cubeUV_maxLods1 (log2(cubeUV_textureSize*0.25) - 1.0)\n#define cubeUV_rangeClamp (exp2((6.0 - 1.0) * 2.0))\nvec2 MipLevelInfo( vec3 vec, float roughnessLevel, float roughness ) {\n\tfloat scale = exp2(cubeUV_maxLods1 - roughnessLevel);\n\tfloat dxRoughness = dFdx(roughness);\n\tfloat dyRoughness = dFdy(roughness);\n\tvec3 dx = dFdx( vec * scale * dxRoughness );\n\tvec3 dy = dFdy( vec * scale * dyRoughness );\n\tfloat d = max( dot( dx, dx ), dot( dy, dy ) );\n\td = clamp(d, 1.0, cubeUV_rangeClamp);\n\tfloat mipLevel = 0.5 * log2(d);\n\treturn vec2(floor(mipLevel), fract(mipLevel));\n}\n#define cubeUV_maxLods2 (log2(cubeUV_textureSize*0.25) - 2.0)\n#define cubeUV_rcpTextureSize (1.0 / cubeUV_textureSize)\nvec2 getCubeUV(vec3 direction, float roughnessLevel, float mipLevel) {\n\tmipLevel = roughnessLevel > cubeUV_maxLods2 - 3.0 ? 0.0 : mipLevel;\n\tfloat a = 16.0 * cubeUV_rcpTextureSize;\n\tvec2 exp2_packed = exp2( vec2( roughnessLevel, mipLevel ) );\n\tvec2 rcp_exp2_packed = vec2( 1.0 ) / exp2_packed;\n\tfloat powScale = exp2_packed.x * exp2_packed.y;\n\tfloat scale = rcp_exp2_packed.x * rcp_exp2_packed.y * 0.25;\n\tfloat mipOffset = 0.75*(1.0 - rcp_exp2_packed.y) * rcp_exp2_packed.x;\n\tbool bRes = mipLevel == 0.0;\n\tscale = bRes && (scale < a) ? a : scale;\n\tvec3 r;\n\tvec2 offset;\n\tint face = getFaceFromDirection(direction);\n\tfloat rcpPowScale = 1.0 / powScale;\n\tif( face == 0) {\n\t\tr = vec3(direction.x, -direction.z, direction.y);\n\t\toffset = vec2(0.0+mipOffset,0.75 * rcpPowScale);\n\t\toffset.y = bRes && (offset.y < 2.0*a) ? a : offset.y;\n\t}\n\telse if( face == 1) {\n\t\tr = vec3(direction.y, direction.x, direction.z);\n\t\toffset = vec2(scale+mipOffset, 0.75 * rcpPowScale);\n\t\toffset.y = bRes && (offset.y < 2.0*a) ? a : offset.y;\n\t}\n\telse if( face == 2) {\n\t\tr = vec3(direction.z, direction.x, direction.y);\n\t\toffset = vec2(2.0*scale+mipOffset, 0.75 * rcpPowScale);\n\t\toffset.y = bRes && (offset.y < 2.0*a) ? a : offset.y;\n\t}\n\telse if( face == 3) {\n\t\tr = vec3(direction.x, direction.z, direction.y);\n\t\toffset = vec2(0.0+mipOffset,0.5 * rcpPowScale);\n\t\toffset.y = bRes && (offset.y < 2.0*a) ? 0.0 : offset.y;\n\t}\n\telse if( face == 4) {\n\t\tr = vec3(direction.y, direction.x, -direction.z);\n\t\toffset = vec2(scale+mipOffset, 0.5 * rcpPowScale);\n\t\toffset.y = bRes && (offset.y < 2.0*a) ? 0.0 : offset.y;\n\t}\n\telse {\n\t\tr = vec3(direction.z, -direction.x, direction.y);\n\t\toffset = vec2(2.0*scale+mipOffset, 0.5 * rcpPowScale);\n\t\toffset.y = bRes && (offset.y < 2.0*a) ? 0.0 : offset.y;\n\t}\n\tr = normalize(r);\n\tfloat texelOffset = 0.5 * cubeUV_rcpTextureSize;\n\tvec2 s = ( r.yz / abs( r.x ) + vec2( 1.0 ) ) * 0.5;\n\tvec2 base = offset + vec2( texelOffset );\n\treturn base + s * ( scale - 2.0 * texelOffset );\n}\n#define cubeUV_maxLods3 (log2(cubeUV_textureSize*0.25) - 3.0)\nvec4 textureCubeUV(vec3 reflectedDirection, float roughness ) {\n\tfloat roughnessVal = roughness* cubeUV_maxLods3;\n\tfloat r1 = floor(roughnessVal);\n\tfloat r2 = r1 + 1.0;\n\tfloat t = fract(roughnessVal);\n\tvec2 mipInfo = MipLevelInfo(reflectedDirection, r1, roughness);\n\tfloat s = mipInfo.y;\n\tfloat level0 = mipInfo.x;\n\tfloat level1 = level0 + 1.0;\n\tlevel1 = level1 > 5.0 ? 5.0 : level1;\n\tlevel0 += min( floor( s + 0.5 ), 5.0 );\n\tvec2 uv_10 = getCubeUV(reflectedDirection, r1, level0);\n\tvec4 color10 = envMapTexelToLinear(texture2D(envMap, uv_10));\n\tvec2 uv_20 = getCubeUV(reflectedDirection, r2, level0);\n\tvec4 color20 = envMapTexelToLinear(texture2D(envMap, uv_20));\n\tvec4 result = mix(color10, color20, t);\n\treturn vec4(result.rgb, 1.0);\n}\n#endif\n";
+
+var defaultnormal_vertex = "vec3 transformedNormal = normalMatrix * objectNormal;\n#ifdef FLIP_SIDED\n\ttransformedNormal = - transformedNormal;\n#endif\n";
+
+var displacementmap_pars_vertex = "#ifdef USE_DISPLACEMENTMAP\n\tuniform sampler2D displacementMap;\n\tuniform float displacementScale;\n\tuniform float displacementBias;\n#endif\n";
+
+var displacementmap_vertex = "#ifdef USE_DISPLACEMENTMAP\n\ttransformed += normalize( objectNormal ) * ( texture2D( displacementMap, uv ).x * displacementScale + displacementBias );\n#endif\n";
+
+var emissivemap_fragment = "#ifdef USE_EMISSIVEMAP\n\tvec4 emissiveColor = texture2D( emissiveMap, vUv );\n\temissiveColor.rgb = emissiveMapTexelToLinear( emissiveColor ).rgb;\n\ttotalEmissiveRadiance *= emissiveColor.rgb;\n#endif\n";
+
+var emissivemap_pars_fragment = "#ifdef USE_EMISSIVEMAP\n\tuniform sampler2D emissiveMap;\n#endif\n";
+
+var encodings_fragment = " gl_FragColor = linearToOutputTexel( gl_FragColor );\n";
+
+var encodings_pars_fragment = "\nvec4 LinearToLinear( in vec4 value ) {\n\treturn value;\n}\nvec4 GammaToLinear( in vec4 value, in float gammaFactor ) {\n\treturn vec4( pow( value.xyz, vec3( gammaFactor ) ), value.w );\n}\nvec4 LinearToGamma( in vec4 value, in float gammaFactor ) {\n\treturn vec4( pow( value.xyz, vec3( 1.0 / gammaFactor ) ), value.w );\n}\nvec4 sRGBToLinear( in vec4 value ) {\n\treturn vec4( mix( pow( value.rgb * 0.9478672986 + vec3( 0.0521327014 ), vec3( 2.4 ) ), value.rgb * 0.0773993808, vec3( lessThanEqual( value.rgb, vec3( 0.04045 ) ) ) ), value.w );\n}\nvec4 LinearTosRGB( in vec4 value ) {\n\treturn vec4( mix( pow( value.rgb, vec3( 0.41666 ) ) * 1.055 - vec3( 0.055 ), value.rgb * 12.92, vec3( lessThanEqual( value.rgb, vec3( 0.0031308 ) ) ) ), value.w );\n}\nvec4 RGBEToLinear( in vec4 value ) {\n\treturn vec4( value.rgb * exp2( value.a * 255.0 - 128.0 ), 1.0 );\n}\nvec4 LinearToRGBE( in vec4 value ) {\n\tfloat maxComponent = max( max( value.r, value.g ), value.b );\n\tfloat fExp = clamp( ceil( log2( maxComponent ) ), -128.0, 127.0 );\n\treturn vec4( value.rgb / exp2( fExp ), ( fExp + 128.0 ) / 255.0 );\n}\nvec4 RGBMToLinear( in vec4 value, in float maxRange ) {\n\treturn vec4( value.xyz * value.w * maxRange, 1.0 );\n}\nvec4 LinearToRGBM( in vec4 value, in float maxRange ) {\n\tfloat maxRGB = max( value.x, max( value.g, value.b ) );\n\tfloat M = clamp( maxRGB / maxRange, 0.0, 1.0 );\n\tM = ceil( M * 255.0 ) / 255.0;\n\treturn vec4( value.rgb / ( M * maxRange ), M );\n}\nvec4 RGBDToLinear( in vec4 value, in float maxRange ) {\n\treturn vec4( value.rgb * ( ( maxRange / 255.0 ) / value.a ), 1.0 );\n}\nvec4 LinearToRGBD( in vec4 value, in float maxRange ) {\n\tfloat maxRGB = max( value.x, max( value.g, value.b ) );\n\tfloat D = max( maxRange / maxRGB, 1.0 );\n\tD = min( floor( D ) / 255.0, 1.0 );\n\treturn vec4( value.rgb * ( D * ( 255.0 / maxRange ) ), D );\n}\nconst mat3 cLogLuvM = mat3( 0.2209, 0.3390, 0.4184, 0.1138, 0.6780, 0.7319, 0.0102, 0.1130, 0.2969 );\nvec4 LinearToLogLuv( in vec4 value ) {\n\tvec3 Xp_Y_XYZp = value.rgb * cLogLuvM;\n\tXp_Y_XYZp = max(Xp_Y_XYZp, vec3(1e-6, 1e-6, 1e-6));\n\tvec4 vResult;\n\tvResult.xy = Xp_Y_XYZp.xy / Xp_Y_XYZp.z;\n\tfloat Le = 2.0 * log2(Xp_Y_XYZp.y) + 127.0;\n\tvResult.w = fract(Le);\n\tvResult.z = (Le - (floor(vResult.w*255.0))/255.0)/255.0;\n\treturn vResult;\n}\nconst mat3 cLogLuvInverseM = mat3( 6.0014, -2.7008, -1.7996, -1.3320, 3.1029, -5.7721, 0.3008, -1.0882, 5.6268 );\nvec4 LogLuvToLinear( in vec4 value ) {\n\tfloat Le = value.z * 255.0 + value.w;\n\tvec3 Xp_Y_XYZp;\n\tXp_Y_XYZp.y = exp2((Le - 127.0) / 2.0);\n\tXp_Y_XYZp.z = Xp_Y_XYZp.y / value.y;\n\tXp_Y_XYZp.x = value.x * Xp_Y_XYZp.z;\n\tvec3 vRGB = Xp_Y_XYZp.rgb * cLogLuvInverseM;\n\treturn vec4( max(vRGB, 0.0), 1.0 );\n}\n";
+
+var envmap_fragment = "#ifdef USE_ENVMAP\n\t#if defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( PHONG )\n\t\tvec3 cameraToVertex = normalize( vWorldPosition - cameraPosition );\n\t\tvec3 worldNormal = inverseTransformDirection( normal, viewMatrix );\n\t\t#ifdef ENVMAP_MODE_REFLECTION\n\t\t\tvec3 reflectVec = reflect( cameraToVertex, worldNormal );\n\t\t#else\n\t\t\tvec3 reflectVec = refract( cameraToVertex, worldNormal, refractionRatio );\n\t\t#endif\n\t#else\n\t\tvec3 reflectVec = vReflect;\n\t#endif\n\t#ifdef ENVMAP_TYPE_CUBE\n\t\tvec4 envColor = textureCube( envMap, vec3( flipEnvMap * reflectVec.x, reflectVec.yz ) );\n\t#elif defined( ENVMAP_TYPE_EQUIREC )\n\t\tvec2 sampleUV;\n\t\treflectVec = normalize( reflectVec );\n\t\tsampleUV.y = asin( clamp( reflectVec.y, - 1.0, 1.0 ) ) * RECIPROCAL_PI + 0.5;\n\t\tsampleUV.x = atan( reflectVec.z, reflectVec.x ) * RECIPROCAL_PI2 + 0.5;\n\t\tvec4 envColor = texture2D( envMap, sampleUV );\n\t#elif defined( ENVMAP_TYPE_SPHERE )\n\t\treflectVec = normalize( reflectVec );\n\t\tvec3 reflectView = normalize( ( viewMatrix * vec4( reflectVec, 0.0 ) ).xyz + vec3( 0.0, 0.0, 1.0 ) );\n\t\tvec4 envColor = texture2D( envMap, reflectView.xy * 0.5 + 0.5 );\n\t#else\n\t\tvec4 envColor = vec4( 0.0 );\n\t#endif\n\tenvColor = envMapTexelToLinear( envColor );\n\t#ifdef ENVMAP_BLENDING_MULTIPLY\n\t\toutgoingLight = mix( outgoingLight, outgoingLight * envColor.xyz, specularStrength * reflectivity );\n\t#elif defined( ENVMAP_BLENDING_MIX )\n\t\toutgoingLight = mix( outgoingLight, envColor.xyz, specularStrength * reflectivity );\n\t#elif defined( ENVMAP_BLENDING_ADD )\n\t\toutgoingLight += envColor.xyz * specularStrength * reflectivity;\n\t#endif\n#endif\n";
+
+var envmap_pars_fragment = "#if defined( USE_ENVMAP ) || defined( PHYSICAL )\n\tuniform float reflectivity;\n\tuniform float envMapIntensity;\n#endif\n#ifdef USE_ENVMAP\n\t#if ! defined( PHYSICAL ) && ( defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( PHONG ) )\n\t\tvarying vec3 vWorldPosition;\n\t#endif\n\t#ifdef ENVMAP_TYPE_CUBE\n\t\tuniform samplerCube envMap;\n\t#else\n\t\tuniform sampler2D envMap;\n\t#endif\n\tuniform float flipEnvMap;\n\t#if defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( PHONG ) || defined( PHYSICAL )\n\t\tuniform float refractionRatio;\n\t#else\n\t\tvarying vec3 vReflect;\n\t#endif\n#endif\n";
+
+var envmap_pars_vertex = "#ifdef USE_ENVMAP\n\t#if defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( PHONG )\n\t\tvarying vec3 vWorldPosition;\n\t#else\n\t\tvarying vec3 vReflect;\n\t\tuniform float refractionRatio;\n\t#endif\n#endif\n";
+
+var envmap_vertex = "#ifdef USE_ENVMAP\n\t#if defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( PHONG )\n\t\tvWorldPosition = worldPosition.xyz;\n\t#else\n\t\tvec3 cameraToVertex = normalize( worldPosition.xyz - cameraPosition );\n\t\tvec3 worldNormal = inverseTransformDirection( transformedNormal, viewMatrix );\n\t\t#ifdef ENVMAP_MODE_REFLECTION\n\t\t\tvReflect = reflect( cameraToVertex, worldNormal );\n\t\t#else\n\t\t\tvReflect = refract( cameraToVertex, worldNormal, refractionRatio );\n\t\t#endif\n\t#endif\n#endif\n";
+
+var fog_vertex = "\n#ifdef USE_FOG\nfogDepth = -mvPosition.z;\n#endif";
+
+var fog_pars_vertex = "#ifdef USE_FOG\n varying float fogDepth;\n#endif\n";
+
+var fog_fragment = "#ifdef USE_FOG\n\t#ifdef FOG_EXP2\n\t\tfloat fogFactor = whiteCompliment( exp2( - fogDensity * fogDensity * fogDepth * fogDepth * LOG2 ) );\n\t#else\n\t\tfloat fogFactor = smoothstep( fogNear, fogFar, fogDepth );\n\t#endif\n\tgl_FragColor.rgb = mix( gl_FragColor.rgb, fogColor, fogFactor );\n#endif\n";
+
+var fog_pars_fragment = "#ifdef USE_FOG\n\tuniform vec3 fogColor;\n\tvarying float fogDepth;\n\t#ifdef FOG_EXP2\n\t\tuniform float fogDensity;\n\t#else\n\t\tuniform float fogNear;\n\t\tuniform float fogFar;\n\t#endif\n#endif\n";
+
+var gradientmap_pars_fragment = "#ifdef TOON\n\tuniform sampler2D gradientMap;\n\tvec3 getGradientIrradiance( vec3 normal, vec3 lightDirection ) {\n\t\tfloat dotNL = dot( normal, lightDirection );\n\t\tvec2 coord = vec2( dotNL * 0.5 + 0.5, 0.0 );\n\t\t#ifdef USE_GRADIENTMAP\n\t\t\treturn texture2D( gradientMap, coord ).rgb;\n\t\t#else\n\t\t\treturn ( coord.x < 0.7 ) ? vec3( 0.7 ) : vec3( 1.0 );\n\t\t#endif\n\t}\n#endif\n";
+
+var lightmap_fragment = "#ifdef USE_LIGHTMAP\n\treflectedLight.indirectDiffuse += PI * texture2D( lightMap, vUv2 ).xyz * lightMapIntensity;\n#endif\n";
+
+var lightmap_pars_fragment = "#ifdef USE_LIGHTMAP\n\tuniform sampler2D lightMap;\n\tuniform float lightMapIntensity;\n#endif";
+
+var lights_lambert_vertex = "vec3 diffuse = vec3( 1.0 );\nGeometricContext geometry;\ngeometry.position = mvPosition.xyz;\ngeometry.normal = normalize( transformedNormal );\ngeometry.viewDir = normalize( -mvPosition.xyz );\nGeometricContext backGeometry;\nbackGeometry.position = geometry.position;\nbackGeometry.normal = -geometry.normal;\nbackGeometry.viewDir = geometry.viewDir;\nvLightFront = vec3( 0.0 );\n#ifdef DOUBLE_SIDED\n\tvLightBack = vec3( 0.0 );\n#endif\nIncidentLight directLight;\nfloat dotNL;\nvec3 directLightColor_Diffuse;\n#if NUM_POINT_LIGHTS > 0\n\tfor ( int i = 0; i < NUM_POINT_LIGHTS; i ++ ) {\n\t\tgetPointDirectLightIrradiance( pointLights[ i ], geometry, directLight );\n\t\tdotNL = dot( geometry.normal, directLight.direction );\n\t\tdirectLightColor_Diffuse = PI * directLight.color;\n\t\tvLightFront += saturate( dotNL ) * directLightColor_Diffuse;\n\t\t#ifdef DOUBLE_SIDED\n\t\t\tvLightBack += saturate( -dotNL ) * directLightColor_Diffuse;\n\t\t#endif\n\t}\n#endif\n#if NUM_SPOT_LIGHTS > 0\n\tfor ( int i = 0; i < NUM_SPOT_LIGHTS; i ++ ) {\n\t\tgetSpotDirectLightIrradiance( spotLights[ i ], geometry, directLight );\n\t\tdotNL = dot( geometry.normal, directLight.direction );\n\t\tdirectLightColor_Diffuse = PI * directLight.color;\n\t\tvLightFront += saturate( dotNL ) * directLightColor_Diffuse;\n\t\t#ifdef DOUBLE_SIDED\n\t\t\tvLightBack += saturate( -dotNL ) * directLightColor_Diffuse;\n\t\t#endif\n\t}\n#endif\n#if NUM_DIR_LIGHTS > 0\n\tfor ( int i = 0; i < NUM_DIR_LIGHTS; i ++ ) {\n\t\tgetDirectionalDirectLightIrradiance( directionalLights[ i ], geometry, directLight );\n\t\tdotNL = dot( geometry.normal, directLight.direction );\n\t\tdirectLightColor_Diffuse = PI * directLight.color;\n\t\tvLightFront += saturate( dotNL ) * directLightColor_Diffuse;\n\t\t#ifdef DOUBLE_SIDED\n\t\t\tvLightBack += saturate( -dotNL ) * directLightColor_Diffuse;\n\t\t#endif\n\t}\n#endif\n#if NUM_HEMI_LIGHTS > 0\n\tfor ( int i = 0; i < NUM_HEMI_LIGHTS; i ++ ) {\n\t\tvLightFront += getHemisphereLightIrradiance( hemisphereLights[ i ], geometry );\n\t\t#ifdef DOUBLE_SIDED\n\t\t\tvLightBack += getHemisphereLightIrradiance( hemisphereLights[ i ], backGeometry );\n\t\t#endif\n\t}\n#endif\n";
+
+var lights_pars = "uniform vec3 ambientLightColor;\nvec3 getAmbientLightIrradiance( const in vec3 ambientLightColor ) {\n\tvec3 irradiance = ambientLightColor;\n\t#ifndef PHYSICALLY_CORRECT_LIGHTS\n\t\tirradiance *= PI;\n\t#endif\n\treturn irradiance;\n}\n#if NUM_DIR_LIGHTS > 0\n\tstruct DirectionalLight {\n\t\tvec3 direction;\n\t\tvec3 color;\n\t\tint shadow;\n\t\tfloat shadowBias;\n\t\tfloat shadowRadius;\n\t\tvec2 shadowMapSize;\n\t};\n\tuniform DirectionalLight directionalLights[ NUM_DIR_LIGHTS ];\n\tvoid getDirectionalDirectLightIrradiance( const in DirectionalLight directionalLight, const in GeometricContext geometry, out IncidentLight directLight ) {\n\t\tdirectLight.color = directionalLight.color;\n\t\tdirectLight.direction = directionalLight.direction;\n\t\tdirectLight.visible = true;\n\t}\n#endif\n#if NUM_POINT_LIGHTS > 0\n\tstruct PointLight {\n\t\tvec3 position;\n\t\tvec3 color;\n\t\tfloat distance;\n\t\tfloat decay;\n\t\tint shadow;\n\t\tfloat shadowBias;\n\t\tfloat shadowRadius;\n\t\tvec2 shadowMapSize;\n\t\tfloat shadowCameraNear;\n\t\tfloat shadowCameraFar;\n\t};\n\tuniform PointLight pointLights[ NUM_POINT_LIGHTS ];\n\tvoid getPointDirectLightIrradiance( const in PointLight pointLight, const in GeometricContext geometry, out IncidentLight directLight ) {\n\t\tvec3 lVector = pointLight.position - geometry.position;\n\t\tdirectLight.direction = normalize( lVector );\n\t\tfloat lightDistance = length( lVector );\n\t\tdirectLight.color = pointLight.color;\n\t\tdirectLight.color *= punctualLightIntensityToIrradianceFactor( lightDistance, pointLight.distance, pointLight.decay );\n\t\tdirectLight.visible = ( directLight.color != vec3( 0.0 ) );\n\t}\n#endif\n#if NUM_SPOT_LIGHTS > 0\n\tstruct SpotLight {\n\t\tvec3 position;\n\t\tvec3 direction;\n\t\tvec3 color;\n\t\tfloat distance;\n\t\tfloat decay;\n\t\tfloat coneCos;\n\t\tfloat penumbraCos;\n\t\tint shadow;\n\t\tfloat shadowBias;\n\t\tfloat shadowRadius;\n\t\tvec2 shadowMapSize;\n\t};\n\tuniform SpotLight spotLights[ NUM_SPOT_LIGHTS ];\n\tvoid getSpotDirectLightIrradiance( const in SpotLight spotLight, const in GeometricContext geometry, out IncidentLight directLight ) {\n\t\tvec3 lVector = spotLight.position - geometry.position;\n\t\tdirectLight.direction = normalize( lVector );\n\t\tfloat lightDistance = length( lVector );\n\t\tfloat angleCos = dot( directLight.direction, spotLight.direction );\n\t\tif ( angleCos > spotLight.coneCos ) {\n\t\t\tfloat spotEffect = smoothstep( spotLight.coneCos, spotLight.penumbraCos, angleCos );\n\t\t\tdirectLight.color = spotLight.color;\n\t\t\tdirectLight.color *= spotEffect * punctualLightIntensityToIrradianceFactor( lightDistance, spotLight.distance, spotLight.decay );\n\t\t\tdirectLight.visible = true;\n\t\t} else {\n\t\t\tdirectLight.color = vec3( 0.0 );\n\t\t\tdirectLight.visible = false;\n\t\t}\n\t}\n#endif\n#if NUM_RECT_AREA_LIGHTS > 0\n\tstruct RectAreaLight {\n\t\tvec3 color;\n\t\tvec3 position;\n\t\tvec3 halfWidth;\n\t\tvec3 halfHeight;\n\t};\n\tuniform sampler2D ltcMat;\tuniform sampler2D ltcMag;\n\tuniform RectAreaLight rectAreaLights[ NUM_RECT_AREA_LIGHTS ];\n#endif\n#if NUM_HEMI_LIGHTS > 0\n\tstruct HemisphereLight {\n\t\tvec3 direction;\n\t\tvec3 skyColor;\n\t\tvec3 groundColor;\n\t};\n\tuniform HemisphereLight hemisphereLights[ NUM_HEMI_LIGHTS ];\n\tvec3 getHemisphereLightIrradiance( const in HemisphereLight hemiLight, const in GeometricContext geometry ) {\n\t\tfloat dotNL = dot( geometry.normal, hemiLight.direction );\n\t\tfloat hemiDiffuseWeight = 0.5 * dotNL + 0.5;\n\t\tvec3 irradiance = mix( hemiLight.groundColor, hemiLight.skyColor, hemiDiffuseWeight );\n\t\t#ifndef PHYSICALLY_CORRECT_LIGHTS\n\t\t\tirradiance *= PI;\n\t\t#endif\n\t\treturn irradiance;\n\t}\n#endif\n#if defined( USE_ENVMAP ) && defined( PHYSICAL )\n\tvec3 getLightProbeIndirectIrradiance( const in GeometricContext geometry, const in int maxMIPLevel ) {\n\t\tvec3 worldNormal = inverseTransformDirection( geometry.normal, viewMatrix );\n\t\t#ifdef ENVMAP_TYPE_CUBE\n\t\t\tvec3 queryVec = vec3( flipEnvMap * worldNormal.x, worldNormal.yz );\n\t\t\t#ifdef TEXTURE_LOD_EXT\n\t\t\t\tvec4 envMapColor = textureCubeLodEXT( envMap, queryVec, float( maxMIPLevel ) );\n\t\t\t#else\n\t\t\t\tvec4 envMapColor = textureCube( envMap, queryVec, float( maxMIPLevel ) );\n\t\t\t#endif\n\t\t\tenvMapColor.rgb = envMapTexelToLinear( envMapColor ).rgb;\n\t\t#elif defined( ENVMAP_TYPE_CUBE_UV )\n\t\t\tvec3 queryVec = vec3( flipEnvMap * worldNormal.x, worldNormal.yz );\n\t\t\tvec4 envMapColor = textureCubeUV( queryVec, 1.0 );\n\t\t#else\n\t\t\tvec4 envMapColor = vec4( 0.0 );\n\t\t#endif\n\t\treturn PI * envMapColor.rgb * envMapIntensity;\n\t}\n\tfloat getSpecularMIPLevel( const in float blinnShininessExponent, const in int maxMIPLevel ) {\n\t\tfloat maxMIPLevelScalar = float( maxMIPLevel );\n\t\tfloat desiredMIPLevel = maxMIPLevelScalar + 0.79248 - 0.5 * log2( pow2( blinnShininessExponent ) + 1.0 );\n\t\treturn clamp( desiredMIPLevel, 0.0, maxMIPLevelScalar );\n\t}\n\tvec3 getLightProbeIndirectRadiance( const in GeometricContext geometry, const in float blinnShininessExponent, const in int maxMIPLevel ) {\n\t\t#ifdef ENVMAP_MODE_REFLECTION\n\t\t\tvec3 reflectVec = reflect( -geometry.viewDir, geometry.normal );\n\t\t#else\n\t\t\tvec3 reflectVec = refract( -geometry.viewDir, geometry.normal, refractionRatio );\n\t\t#endif\n\t\treflectVec = inverseTransformDirection( reflectVec, viewMatrix );\n\t\tfloat specularMIPLevel = getSpecularMIPLevel( blinnShininessExponent, maxMIPLevel );\n\t\t#ifdef ENVMAP_TYPE_CUBE\n\t\t\tvec3 queryReflectVec = vec3( flipEnvMap * reflectVec.x, reflectVec.yz );\n\t\t\t#ifdef TEXTURE_LOD_EXT\n\t\t\t\tvec4 envMapColor = textureCubeLodEXT( envMap, queryReflectVec, specularMIPLevel );\n\t\t\t#else\n\t\t\t\tvec4 envMapColor = textureCube( envMap, queryReflectVec, specularMIPLevel );\n\t\t\t#endif\n\t\t\tenvMapColor.rgb = envMapTexelToLinear( envMapColor ).rgb;\n\t\t#elif defined( ENVMAP_TYPE_CUBE_UV )\n\t\t\tvec3 queryReflectVec = vec3( flipEnvMap * reflectVec.x, reflectVec.yz );\n\t\t\tvec4 envMapColor = textureCubeUV(queryReflectVec, BlinnExponentToGGXRoughness(blinnShininessExponent));\n\t\t#elif defined( ENVMAP_TYPE_EQUIREC )\n\t\t\tvec2 sampleUV;\n\t\t\tsampleUV.y = asin( clamp( reflectVec.y, - 1.0, 1.0 ) ) * RECIPROCAL_PI + 0.5;\n\t\t\tsampleUV.x = atan( reflectVec.z, reflectVec.x ) * RECIPROCAL_PI2 + 0.5;\n\t\t\t#ifdef TEXTURE_LOD_EXT\n\t\t\t\tvec4 envMapColor = texture2DLodEXT( envMap, sampleUV, specularMIPLevel );\n\t\t\t#else\n\t\t\t\tvec4 envMapColor = texture2D( envMap, sampleUV, specularMIPLevel );\n\t\t\t#endif\n\t\t\tenvMapColor.rgb = envMapTexelToLinear( envMapColor ).rgb;\n\t\t#elif defined( ENVMAP_TYPE_SPHERE )\n\t\t\tvec3 reflectView = normalize( ( viewMatrix * vec4( reflectVec, 0.0 ) ).xyz + vec3( 0.0,0.0,1.0 ) );\n\t\t\t#ifdef TEXTURE_LOD_EXT\n\t\t\t\tvec4 envMapColor = texture2DLodEXT( envMap, reflectView.xy * 0.5 + 0.5, specularMIPLevel );\n\t\t\t#else\n\t\t\t\tvec4 envMapColor = texture2D( envMap, reflectView.xy * 0.5 + 0.5, specularMIPLevel );\n\t\t\t#endif\n\t\t\tenvMapColor.rgb = envMapTexelToLinear( envMapColor ).rgb;\n\t\t#endif\n\t\treturn envMapColor.rgb * envMapIntensity;\n\t}\n#endif\n";
+
+var lights_phong_fragment = "BlinnPhongMaterial material;\nmaterial.diffuseColor = diffuseColor.rgb;\nmaterial.specularColor = specular;\nmaterial.specularShininess = shininess;\nmaterial.specularStrength = specularStrength;\n";
+
+var lights_phong_pars_fragment = "varying vec3 vViewPosition;\n#ifndef FLAT_SHADED\n\tvarying vec3 vNormal;\n#endif\nstruct BlinnPhongMaterial {\n\tvec3\tdiffuseColor;\n\tvec3\tspecularColor;\n\tfloat\tspecularShininess;\n\tfloat\tspecularStrength;\n};\nvoid RE_Direct_BlinnPhong( const in IncidentLight directLight, const in GeometricContext geometry, const in BlinnPhongMaterial material, inout ReflectedLight reflectedLight ) {\n\t#ifdef TOON\n\t\tvec3 irradiance = getGradientIrradiance( geometry.normal, directLight.direction ) * directLight.color;\n\t#else\n\t\tfloat dotNL = saturate( dot( geometry.normal, directLight.direction ) );\n\t\tvec3 irradiance = dotNL * directLight.color;\n\t#endif\n\t#ifndef PHYSICALLY_CORRECT_LIGHTS\n\t\tirradiance *= PI;\n\t#endif\n\treflectedLight.directDiffuse += irradiance * BRDF_Diffuse_Lambert( material.diffuseColor );\n\treflectedLight.directSpecular += irradiance * BRDF_Specular_BlinnPhong( directLight, geometry, material.specularColor, material.specularShininess ) * material.specularStrength;\n}\nvoid RE_IndirectDiffuse_BlinnPhong( const in vec3 irradiance, const in GeometricContext geometry, const in BlinnPhongMaterial material, inout ReflectedLight reflectedLight ) {\n\treflectedLight.indirectDiffuse += irradiance * BRDF_Diffuse_Lambert( material.diffuseColor );\n}\n#define RE_Direct\t\t\t\tRE_Direct_BlinnPhong\n#define RE_IndirectDiffuse\t\tRE_IndirectDiffuse_BlinnPhong\n#define Material_LightProbeLOD( material )\t(0)\n";
+
+var lights_physical_fragment = "PhysicalMaterial material;\nmaterial.diffuseColor = diffuseColor.rgb * ( 1.0 - metalnessFactor );\nmaterial.specularRoughness = clamp( roughnessFactor, 0.04, 1.0 );\n#ifdef STANDARD\n\tmaterial.specularColor = mix( vec3( DEFAULT_SPECULAR_COEFFICIENT ), diffuseColor.rgb, metalnessFactor );\n#else\n\tmaterial.specularColor = mix( vec3( MAXIMUM_SPECULAR_COEFFICIENT * pow2( reflectivity ) ), diffuseColor.rgb, metalnessFactor );\n\tmaterial.clearCoat = saturate( clearCoat );\tmaterial.clearCoatRoughness = clamp( clearCoatRoughness, 0.04, 1.0 );\n#endif\n";
+
+var lights_physical_pars_fragment = "struct PhysicalMaterial {\n\tvec3\tdiffuseColor;\n\tfloat\tspecularRoughness;\n\tvec3\tspecularColor;\n\t#ifndef STANDARD\n\t\tfloat clearCoat;\n\t\tfloat clearCoatRoughness;\n\t#endif\n};\n#define MAXIMUM_SPECULAR_COEFFICIENT 0.16\n#define DEFAULT_SPECULAR_COEFFICIENT 0.04\nfloat clearCoatDHRApprox( const in float roughness, const in float dotNL ) {\n\treturn DEFAULT_SPECULAR_COEFFICIENT + ( 1.0 - DEFAULT_SPECULAR_COEFFICIENT ) * ( pow( 1.0 - dotNL, 5.0 ) * pow( 1.0 - roughness, 2.0 ) );\n}\n#if NUM_RECT_AREA_LIGHTS > 0\n\tvoid RE_Direct_RectArea_Physical( const in RectAreaLight rectAreaLight, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {\n\t\tvec3 normal = geometry.normal;\n\t\tvec3 viewDir = geometry.viewDir;\n\t\tvec3 position = geometry.position;\n\t\tvec3 lightPos = rectAreaLight.position;\n\t\tvec3 halfWidth = rectAreaLight.halfWidth;\n\t\tvec3 halfHeight = rectAreaLight.halfHeight;\n\t\tvec3 lightColor = rectAreaLight.color;\n\t\tfloat roughness = material.specularRoughness;\n\t\tvec3 rectCoords[ 4 ];\n\t\trectCoords[ 0 ] = lightPos - halfWidth - halfHeight;\t\trectCoords[ 1 ] = lightPos + halfWidth - halfHeight;\n\t\trectCoords[ 2 ] = lightPos + halfWidth + halfHeight;\n\t\trectCoords[ 3 ] = lightPos - halfWidth + halfHeight;\n\t\tvec2 uv = LTC_Uv( normal, viewDir, roughness );\n\t\tfloat norm = texture2D( ltcMag, uv ).a;\n\t\tvec4 t = texture2D( ltcMat, uv );\n\t\tmat3 mInv = mat3(\n\t\t\tvec3( 1, 0, t.y ),\n\t\t\tvec3( 0, t.z, 0 ),\n\t\t\tvec3( t.w, 0, t.x )\n\t\t);\n\t\treflectedLight.directSpecular += lightColor * material.specularColor * norm * LTC_Evaluate( normal, viewDir, position, mInv, rectCoords );\n\t\treflectedLight.directDiffuse += lightColor * material.diffuseColor * LTC_Evaluate( normal, viewDir, position, mat3( 1 ), rectCoords );\n\t}\n#endif\nvoid RE_Direct_Physical( const in IncidentLight directLight, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {\n\tfloat dotNL = saturate( dot( geometry.normal, directLight.direction ) );\n\tvec3 irradiance = dotNL * directLight.color;\n\t#ifndef PHYSICALLY_CORRECT_LIGHTS\n\t\tirradiance *= PI;\n\t#endif\n\t#ifndef STANDARD\n\t\tfloat clearCoatDHR = material.clearCoat * clearCoatDHRApprox( material.clearCoatRoughness, dotNL );\n\t#else\n\t\tfloat clearCoatDHR = 0.0;\n\t#endif\n\treflectedLight.directSpecular += ( 1.0 - clearCoatDHR ) * irradiance * BRDF_Specular_GGX( directLight, geometry, material.specularColor, material.specularRoughness );\n\treflectedLight.directDiffuse += ( 1.0 - clearCoatDHR ) * irradiance * BRDF_Diffuse_Lambert( material.diffuseColor );\n\t#ifndef STANDARD\n\t\treflectedLight.directSpecular += irradiance * material.clearCoat * BRDF_Specular_GGX( directLight, geometry, vec3( DEFAULT_SPECULAR_COEFFICIENT ), material.clearCoatRoughness );\n\t#endif\n}\nvoid RE_IndirectDiffuse_Physical( const in vec3 irradiance, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {\n\treflectedLight.indirectDiffuse += irradiance * BRDF_Diffuse_Lambert( material.diffuseColor );\n}\nvoid RE_IndirectSpecular_Physical( const in vec3 radiance, const in vec3 clearCoatRadiance, const in GeometricContext geometry, const in PhysicalMaterial material, inout ReflectedLight reflectedLight ) {\n\t#ifndef STANDARD\n\t\tfloat dotNV = saturate( dot( geometry.normal, geometry.viewDir ) );\n\t\tfloat dotNL = dotNV;\n\t\tfloat clearCoatDHR = material.clearCoat * clearCoatDHRApprox( material.clearCoatRoughness, dotNL );\n\t#else\n\t\tfloat clearCoatDHR = 0.0;\n\t#endif\n\treflectedLight.indirectSpecular += ( 1.0 - clearCoatDHR ) * radiance * BRDF_Specular_GGX_Environment( geometry, material.specularColor, material.specularRoughness );\n\t#ifndef STANDARD\n\t\treflectedLight.indirectSpecular += clearCoatRadiance * material.clearCoat * BRDF_Specular_GGX_Environment( geometry, vec3( DEFAULT_SPECULAR_COEFFICIENT ), material.clearCoatRoughness );\n\t#endif\n}\n#define RE_Direct\t\t\t\tRE_Direct_Physical\n#define RE_Direct_RectArea\t\tRE_Direct_RectArea_Physical\n#define RE_IndirectDiffuse\t\tRE_IndirectDiffuse_Physical\n#define RE_IndirectSpecular\t\tRE_IndirectSpecular_Physical\n#define Material_BlinnShininessExponent( material ) GGXRoughnessToBlinnExponent( material.specularRoughness )\n#define Material_ClearCoat_BlinnShininessExponent( material ) GGXRoughnessToBlinnExponent( material.clearCoatRoughness )\nfloat computeSpecularOcclusion( const in float dotNV, const in float ambientOcclusion, const in float roughness ) {\n\treturn saturate( pow( dotNV + ambientOcclusion, exp2( - 16.0 * roughness - 1.0 ) ) - 1.0 + ambientOcclusion );\n}\n";
+
+var lights_template = "\nGeometricContext geometry;\ngeometry.position = - vViewPosition;\ngeometry.normal = normal;\ngeometry.viewDir = normalize( vViewPosition );\nIncidentLight directLight;\n#if ( NUM_POINT_LIGHTS > 0 ) && defined( RE_Direct )\n\tPointLight pointLight;\n\tfor ( int i = 0; i < NUM_POINT_LIGHTS; i ++ ) {\n\t\tpointLight = pointLights[ i ];\n\t\tgetPointDirectLightIrradiance( pointLight, geometry, directLight );\n\t\t#ifdef USE_SHADOWMAP\n\t\tdirectLight.color *= all( bvec2( pointLight.shadow, directLight.visible ) ) ? getPointShadow( pointShadowMap[ i ], pointLight.shadowMapSize, pointLight.shadowBias, pointLight.shadowRadius, vPointShadowCoord[ i ], pointLight.shadowCameraNear, pointLight.shadowCameraFar ) : 1.0;\n\t\t#endif\n\t\tRE_Direct( directLight, geometry, material, reflectedLight );\n\t}\n#endif\n#if ( NUM_SPOT_LIGHTS > 0 ) && defined( RE_Direct )\n\tSpotLight spotLight;\n\tfor ( int i = 0; i < NUM_SPOT_LIGHTS; i ++ ) {\n\t\tspotLight = spotLights[ i ];\n\t\tgetSpotDirectLightIrradiance( spotLight, geometry, directLight );\n\t\t#ifdef USE_SHADOWMAP\n\t\tdirectLight.color *= all( bvec2( spotLight.shadow, directLight.visible ) ) ? getShadow( spotShadowMap[ i ], spotLight.shadowMapSize, spotLight.shadowBias, spotLight.shadowRadius, vSpotShadowCoord[ i ] ) : 1.0;\n\t\t#endif\n\t\tRE_Direct( directLight, geometry, material, reflectedLight );\n\t}\n#endif\n#if ( NUM_DIR_LIGHTS > 0 ) && defined( RE_Direct )\n\tDirectionalLight directionalLight;\n\tfor ( int i = 0; i < NUM_DIR_LIGHTS; i ++ ) {\n\t\tdirectionalLight = directionalLights[ i ];\n\t\tgetDirectionalDirectLightIrradiance( directionalLight, geometry, directLight );\n\t\t#ifdef USE_SHADOWMAP\n\t\tdirectLight.color *= all( bvec2( directionalLight.shadow, directLight.visible ) ) ? getShadow( directionalShadowMap[ i ], directionalLight.shadowMapSize, directionalLight.shadowBias, directionalLight.shadowRadius, vDirectionalShadowCoord[ i ] ) : 1.0;\n\t\t#endif\n\t\tRE_Direct( directLight, geometry, material, reflectedLight );\n\t}\n#endif\n#if ( NUM_RECT_AREA_LIGHTS > 0 ) && defined( RE_Direct_RectArea )\n\tRectAreaLight rectAreaLight;\n\tfor ( int i = 0; i < NUM_RECT_AREA_LIGHTS; i ++ ) {\n\t\trectAreaLight = rectAreaLights[ i ];\n\t\tRE_Direct_RectArea( rectAreaLight, geometry, material, reflectedLight );\n\t}\n#endif\n#if defined( RE_IndirectDiffuse )\n\tvec3 irradiance = getAmbientLightIrradiance( ambientLightColor );\n\t#ifdef USE_LIGHTMAP\n\t\tvec3 lightMapIrradiance = texture2D( lightMap, vUv2 ).xyz * lightMapIntensity;\n\t\t#ifndef PHYSICALLY_CORRECT_LIGHTS\n\t\t\tlightMapIrradiance *= PI;\n\t\t#endif\n\t\tirradiance += lightMapIrradiance;\n\t#endif\n\t#if ( NUM_HEMI_LIGHTS > 0 )\n\t\tfor ( int i = 0; i < NUM_HEMI_LIGHTS; i ++ ) {\n\t\t\tirradiance += getHemisphereLightIrradiance( hemisphereLights[ i ], geometry );\n\t\t}\n\t#endif\n\t#if defined( USE_ENVMAP ) && defined( PHYSICAL ) && defined( ENVMAP_TYPE_CUBE_UV )\n\t\tirradiance += getLightProbeIndirectIrradiance( geometry, 8 );\n\t#endif\n\tRE_IndirectDiffuse( irradiance, geometry, material, reflectedLight );\n#endif\n#if defined( USE_ENVMAP ) && defined( RE_IndirectSpecular )\n\tvec3 radiance = getLightProbeIndirectRadiance( geometry, Material_BlinnShininessExponent( material ), 8 );\n\t#ifndef STANDARD\n\t\tvec3 clearCoatRadiance = getLightProbeIndirectRadiance( geometry, Material_ClearCoat_BlinnShininessExponent( material ), 8 );\n\t#else\n\t\tvec3 clearCoatRadiance = vec3( 0.0 );\n\t#endif\n\tRE_IndirectSpecular( radiance, clearCoatRadiance, geometry, material, reflectedLight );\n#endif\n";
+
+var logdepthbuf_fragment = "#if defined( USE_LOGDEPTHBUF ) && defined( USE_LOGDEPTHBUF_EXT )\n\tgl_FragDepthEXT = log2( vFragDepth ) * logDepthBufFC * 0.5;\n#endif";
+
+var logdepthbuf_pars_fragment = "#ifdef USE_LOGDEPTHBUF\n\tuniform float logDepthBufFC;\n\t#ifdef USE_LOGDEPTHBUF_EXT\n\t\tvarying float vFragDepth;\n\t#endif\n#endif\n";
+
+var logdepthbuf_pars_vertex = "#ifdef USE_LOGDEPTHBUF\n\t#ifdef USE_LOGDEPTHBUF_EXT\n\t\tvarying float vFragDepth;\n\t#endif\n\tuniform float logDepthBufFC;\n#endif";
+
+var logdepthbuf_vertex = "#ifdef USE_LOGDEPTHBUF\n\t#ifdef USE_LOGDEPTHBUF_EXT\n\t\tvFragDepth = 1.0 + gl_Position.w;\n\t#else\n\t\tgl_Position.z = log2( max( EPSILON, gl_Position.w + 1.0 ) ) * logDepthBufFC - 1.0;\n\t\tgl_Position.z *= gl_Position.w;\n\t#endif\n#endif\n";
+
+var map_fragment = "#ifdef USE_MAP\n\tvec4 texelColor = texture2D( map, vUv );\n\ttexelColor = mapTexelToLinear( texelColor );\n\tdiffuseColor *= texelColor;\n#endif\n";
+
+var map_pars_fragment = "#ifdef USE_MAP\n\tuniform sampler2D map;\n#endif\n";
+
+var map_particle_fragment = "#ifdef USE_MAP\n\tvec2 uv = ( uvTransform * vec3( gl_PointCoord.x, 1.0 - gl_PointCoord.y, 1 ) ).xy;\n\tvec4 mapTexel = texture2D( map, uv );\n\tdiffuseColor *= mapTexelToLinear( mapTexel );\n#endif\n";
+
+var map_particle_pars_fragment = "#ifdef USE_MAP\n\tuniform mat3 uvTransform;\n\tuniform sampler2D map;\n#endif\n";
+
+var metalnessmap_fragment = "float metalnessFactor = metalness;\n#ifdef USE_METALNESSMAP\n\tvec4 texelMetalness = texture2D( metalnessMap, vUv );\n\tmetalnessFactor *= texelMetalness.b;\n#endif\n";
+
+var metalnessmap_pars_fragment = "#ifdef USE_METALNESSMAP\n\tuniform sampler2D metalnessMap;\n#endif";
+
+var morphnormal_vertex = "#ifdef USE_MORPHNORMALS\n\tobjectNormal += ( morphNormal0 - normal ) * morphTargetInfluences[ 0 ];\n\tobjectNormal += ( morphNormal1 - normal ) * morphTargetInfluences[ 1 ];\n\tobjectNormal += ( morphNormal2 - normal ) * morphTargetInfluences[ 2 ];\n\tobjectNormal += ( morphNormal3 - normal ) * morphTargetInfluences[ 3 ];\n#endif\n";
+
+var morphtarget_pars_vertex = "#ifdef USE_MORPHTARGETS\n\t#ifndef USE_MORPHNORMALS\n\tuniform float morphTargetInfluences[ 8 ];\n\t#else\n\tuniform float morphTargetInfluences[ 4 ];\n\t#endif\n#endif";
+
+var morphtarget_vertex = "#ifdef USE_MORPHTARGETS\n\ttransformed += ( morphTarget0 - position ) * morphTargetInfluences[ 0 ];\n\ttransformed += ( morphTarget1 - position ) * morphTargetInfluences[ 1 ];\n\ttransformed += ( morphTarget2 - position ) * morphTargetInfluences[ 2 ];\n\ttransformed += ( morphTarget3 - position ) * morphTargetInfluences[ 3 ];\n\t#ifndef USE_MORPHNORMALS\n\ttransformed += ( morphTarget4 - position ) * morphTargetInfluences[ 4 ];\n\ttransformed += ( morphTarget5 - position ) * morphTargetInfluences[ 5 ];\n\ttransformed += ( morphTarget6 - position ) * morphTargetInfluences[ 6 ];\n\ttransformed += ( morphTarget7 - position ) * morphTargetInfluences[ 7 ];\n\t#endif\n#endif\n";
+
+var normal_fragment = "#ifdef FLAT_SHADED\n\tvec3 fdx = vec3( dFdx( vViewPosition.x ), dFdx( vViewPosition.y ), dFdx( vViewPosition.z ) );\n\tvec3 fdy = vec3( dFdy( vViewPosition.x ), dFdy( vViewPosition.y ), dFdy( vViewPosition.z ) );\n\tvec3 normal = normalize( cross( fdx, fdy ) );\n#else\n\tvec3 normal = normalize( vNormal );\n\t#ifdef DOUBLE_SIDED\n\t\tnormal = normal * ( float( gl_FrontFacing ) * 2.0 - 1.0 );\n\t#endif\n#endif\n#ifdef USE_NORMALMAP\n\tnormal = perturbNormal2Arb( -vViewPosition, normal );\n#elif defined( USE_BUMPMAP )\n\tnormal = perturbNormalArb( -vViewPosition, normal, dHdxy_fwd() );\n#endif\n";
+
+var normalmap_pars_fragment = "#ifdef USE_NORMALMAP\n\tuniform sampler2D normalMap;\n\tuniform vec2 normalScale;\n\tvec3 perturbNormal2Arb( vec3 eye_pos, vec3 surf_norm ) {\n\t\tvec3 q0 = vec3( dFdx( eye_pos.x ), dFdx( eye_pos.y ), dFdx( eye_pos.z ) );\n\t\tvec3 q1 = vec3( dFdy( eye_pos.x ), dFdy( eye_pos.y ), dFdy( eye_pos.z ) );\n\t\tvec2 st0 = dFdx( vUv.st );\n\t\tvec2 st1 = dFdy( vUv.st );\n\t\tvec3 S = normalize( q0 * st1.t - q1 * st0.t );\n\t\tvec3 T = normalize( -q0 * st1.s + q1 * st0.s );\n\t\tvec3 N = normalize( surf_norm );\n\t\tvec3 mapN = texture2D( normalMap, vUv ).xyz * 2.0 - 1.0;\n\t\tmapN.xy = normalScale * mapN.xy;\n\t\tmat3 tsn = mat3( S, T, N );\n\t\treturn normalize( tsn * mapN );\n\t}\n#endif\n";
+
+var packing = "vec3 packNormalToRGB( const in vec3 normal ) {\n\treturn normalize( normal ) * 0.5 + 0.5;\n}\nvec3 unpackRGBToNormal( const in vec3 rgb ) {\n\treturn 2.0 * rgb.xyz - 1.0;\n}\nconst float PackUpscale = 256. / 255.;const float UnpackDownscale = 255. / 256.;\nconst vec3 PackFactors = vec3( 256. * 256. * 256., 256. * 256., 256. );\nconst vec4 UnpackFactors = UnpackDownscale / vec4( PackFactors, 1. );\nconst float ShiftRight8 = 1. / 256.;\nvec4 packDepthToRGBA( const in float v ) {\n\tvec4 r = vec4( fract( v * PackFactors ), v );\n\tr.yzw -= r.xyz * ShiftRight8;\treturn r * PackUpscale;\n}\nfloat unpackRGBAToDepth( const in vec4 v ) {\n\treturn dot( v, UnpackFactors );\n}\nfloat viewZToOrthographicDepth( const in float viewZ, const in float near, const in float far ) {\n\treturn ( viewZ + near ) / ( near - far );\n}\nfloat orthographicDepthToViewZ( const in float linearClipZ, const in float near, const in float far ) {\n\treturn linearClipZ * ( near - far ) - near;\n}\nfloat viewZToPerspectiveDepth( const in float viewZ, const in float near, const in float far ) {\n\treturn (( near + viewZ ) * far ) / (( far - near ) * viewZ );\n}\nfloat perspectiveDepthToViewZ( const in float invClipZ, const in float near, const in float far ) {\n\treturn ( near * far ) / ( ( far - near ) * invClipZ - far );\n}\n";
+
+var premultiplied_alpha_fragment = "#ifdef PREMULTIPLIED_ALPHA\n\tgl_FragColor.rgb *= gl_FragColor.a;\n#endif\n";
+
+var project_vertex = "vec4 mvPosition = modelViewMatrix * vec4( transformed, 1.0 );\ngl_Position = projectionMatrix * mvPosition;\n";
+
+var dithering_fragment = "#if defined( DITHERING )\n gl_FragColor.rgb = dithering( gl_FragColor.rgb );\n#endif\n";
+
+var dithering_pars_fragment = "#if defined( DITHERING )\n\tvec3 dithering( vec3 color ) {\n\t\tfloat grid_position = rand( gl_FragCoord.xy );\n\t\tvec3 dither_shift_RGB = vec3( 0.25 / 255.0, -0.25 / 255.0, 0.25 / 255.0 );\n\t\tdither_shift_RGB = mix( 2.0 * dither_shift_RGB, -2.0 * dither_shift_RGB, grid_position );\n\t\treturn color + dither_shift_RGB;\n\t}\n#endif\n";
+
+var roughnessmap_fragment = "float roughnessFactor = roughness;\n#ifdef USE_ROUGHNESSMAP\n\tvec4 texelRoughness = texture2D( roughnessMap, vUv );\n\troughnessFactor *= texelRoughness.g;\n#endif\n";
+
+var roughnessmap_pars_fragment = "#ifdef USE_ROUGHNESSMAP\n\tuniform sampler2D roughnessMap;\n#endif";
+
+var shadowmap_pars_fragment = "#ifdef USE_SHADOWMAP\n\t#if NUM_DIR_LIGHTS > 0\n\t\tuniform sampler2D directionalShadowMap[ NUM_DIR_LIGHTS ];\n\t\tvarying vec4 vDirectionalShadowCoord[ NUM_DIR_LIGHTS ];\n\t#endif\n\t#if NUM_SPOT_LIGHTS > 0\n\t\tuniform sampler2D spotShadowMap[ NUM_SPOT_LIGHTS ];\n\t\tvarying vec4 vSpotShadowCoord[ NUM_SPOT_LIGHTS ];\n\t#endif\n\t#if NUM_POINT_LIGHTS > 0\n\t\tuniform sampler2D pointShadowMap[ NUM_POINT_LIGHTS ];\n\t\tvarying vec4 vPointShadowCoord[ NUM_POINT_LIGHTS ];\n\t#endif\n\tfloat texture2DCompare( sampler2D depths, vec2 uv, float compare ) {\n\t\treturn step( compare, unpackRGBAToDepth( texture2D( depths, uv ) ) );\n\t}\n\tfloat texture2DShadowLerp( sampler2D depths, vec2 size, vec2 uv, float compare ) {\n\t\tconst vec2 offset = vec2( 0.0, 1.0 );\n\t\tvec2 texelSize = vec2( 1.0 ) / size;\n\t\tvec2 centroidUV = floor( uv * size + 0.5 ) / size;\n\t\tfloat lb = texture2DCompare( depths, centroidUV + texelSize * offset.xx, compare );\n\t\tfloat lt = texture2DCompare( depths, centroidUV + texelSize * offset.xy, compare );\n\t\tfloat rb = texture2DCompare( depths, centroidUV + texelSize * offset.yx, compare );\n\t\tfloat rt = texture2DCompare( depths, centroidUV + texelSize * offset.yy, compare );\n\t\tvec2 f = fract( uv * size + 0.5 );\n\t\tfloat a = mix( lb, lt, f.y );\n\t\tfloat b = mix( rb, rt, f.y );\n\t\tfloat c = mix( a, b, f.x );\n\t\treturn c;\n\t}\n\tfloat getShadow( sampler2D shadowMap, vec2 shadowMapSize, float shadowBias, float shadowRadius, vec4 shadowCoord ) {\n\t\tfloat shadow = 1.0;\n\t\tshadowCoord.xyz /= shadowCoord.w;\n\t\tshadowCoord.z += shadowBias;\n\t\tbvec4 inFrustumVec = bvec4 ( shadowCoord.x >= 0.0, shadowCoord.x <= 1.0, shadowCoord.y >= 0.0, shadowCoord.y <= 1.0 );\n\t\tbool inFrustum = all( inFrustumVec );\n\t\tbvec2 frustumTestVec = bvec2( inFrustum, shadowCoord.z <= 1.0 );\n\t\tbool frustumTest = all( frustumTestVec );\n\t\tif ( frustumTest ) {\n\t\t#if defined( SHADOWMAP_TYPE_PCF )\n\t\t\tvec2 texelSize = vec2( 1.0 ) / shadowMapSize;\n\t\t\tfloat dx0 = - texelSize.x * shadowRadius;\n\t\t\tfloat dy0 = - texelSize.y * shadowRadius;\n\t\t\tfloat dx1 = + texelSize.x * shadowRadius;\n\t\t\tfloat dy1 = + texelSize.y * shadowRadius;\n\t\t\tshadow = (\n\t\t\t\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, dy0 ), shadowCoord.z ) +\n\t\t\t\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy0 ), shadowCoord.z ) +\n\t\t\t\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, dy0 ), shadowCoord.z ) +\n\t\t\t\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, 0.0 ), shadowCoord.z ) +\n\t\t\t\ttexture2DCompare( shadowMap, shadowCoord.xy, shadowCoord.z ) +\n\t\t\t\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, 0.0 ), shadowCoord.z ) +\n\t\t\t\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx0, dy1 ), shadowCoord.z ) +\n\t\t\t\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( 0.0, dy1 ), shadowCoord.z ) +\n\t\t\t\ttexture2DCompare( shadowMap, shadowCoord.xy + vec2( dx1, dy1 ), shadowCoord.z )\n\t\t\t) * ( 1.0 / 9.0 );\n\t\t#elif defined( SHADOWMAP_TYPE_PCF_SOFT )\n\t\t\tvec2 texelSize = vec2( 1.0 ) / shadowMapSize;\n\t\t\tfloat dx0 = - texelSize.x * shadowRadius;\n\t\t\tfloat dy0 = - texelSize.y * shadowRadius;\n\t\t\tfloat dx1 = + texelSize.x * shadowRadius;\n\t\t\tfloat dy1 = + texelSize.y * shadowRadius;\n\t\t\tshadow = (\n\t\t\t\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx0, dy0 ), shadowCoord.z ) +\n\t\t\t\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( 0.0, dy0 ), shadowCoord.z ) +\n\t\t\t\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx1, dy0 ), shadowCoord.z ) +\n\t\t\t\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx0, 0.0 ), shadowCoord.z ) +\n\t\t\t\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy, shadowCoord.z ) +\n\t\t\t\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx1, 0.0 ), shadowCoord.z ) +\n\t\t\t\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx0, dy1 ), shadowCoord.z ) +\n\t\t\t\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( 0.0, dy1 ), shadowCoord.z ) +\n\t\t\t\ttexture2DShadowLerp( shadowMap, shadowMapSize, shadowCoord.xy + vec2( dx1, dy1 ), shadowCoord.z )\n\t\t\t) * ( 1.0 / 9.0 );\n\t\t#else\n\t\t\tshadow = texture2DCompare( shadowMap, shadowCoord.xy, shadowCoord.z );\n\t\t#endif\n\t\t}\n\t\treturn shadow;\n\t}\n\tvec2 cubeToUV( vec3 v, float texelSizeY ) {\n\t\tvec3 absV = abs( v );\n\t\tfloat scaleToCube = 1.0 / max( absV.x, max( absV.y, absV.z ) );\n\t\tabsV *= scaleToCube;\n\t\tv *= scaleToCube * ( 1.0 - 2.0 * texelSizeY );\n\t\tvec2 planar = v.xy;\n\t\tfloat almostATexel = 1.5 * texelSizeY;\n\t\tfloat almostOne = 1.0 - almostATexel;\n\t\tif ( absV.z >= almostOne ) {\n\t\t\tif ( v.z > 0.0 )\n\t\t\t\tplanar.x = 4.0 - v.x;\n\t\t} else if ( absV.x >= almostOne ) {\n\t\t\tfloat signX = sign( v.x );\n\t\t\tplanar.x = v.z * signX + 2.0 * signX;\n\t\t} else if ( absV.y >= almostOne ) {\n\t\t\tfloat signY = sign( v.y );\n\t\t\tplanar.x = v.x + 2.0 * signY + 2.0;\n\t\t\tplanar.y = v.z * signY - 2.0;\n\t\t}\n\t\treturn vec2( 0.125, 0.25 ) * planar + vec2( 0.375, 0.75 );\n\t}\n\tfloat getPointShadow( sampler2D shadowMap, vec2 shadowMapSize, float shadowBias, float shadowRadius, vec4 shadowCoord, float shadowCameraNear, float shadowCameraFar ) {\n\t\tvec2 texelSize = vec2( 1.0 ) / ( shadowMapSize * vec2( 4.0, 2.0 ) );\n\t\tvec3 lightToPosition = shadowCoord.xyz;\n\t\tfloat dp = ( length( lightToPosition ) - shadowCameraNear ) / ( shadowCameraFar - shadowCameraNear );\t\tdp += shadowBias;\n\t\tvec3 bd3D = normalize( lightToPosition );\n\t\t#if defined( SHADOWMAP_TYPE_PCF ) || defined( SHADOWMAP_TYPE_PCF_SOFT )\n\t\t\tvec2 offset = vec2( - 1, 1 ) * shadowRadius * texelSize.y;\n\t\t\treturn (\n\t\t\t\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xyy, texelSize.y ), dp ) +\n\t\t\t\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yyy, texelSize.y ), dp ) +\n\t\t\t\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xyx, texelSize.y ), dp ) +\n\t\t\t\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yyx, texelSize.y ), dp ) +\n\t\t\t\ttexture2DCompare( shadowMap, cubeToUV( bd3D, texelSize.y ), dp ) +\n\t\t\t\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xxy, texelSize.y ), dp ) +\n\t\t\t\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yxy, texelSize.y ), dp ) +\n\t\t\t\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.xxx, texelSize.y ), dp ) +\n\t\t\t\ttexture2DCompare( shadowMap, cubeToUV( bd3D + offset.yxx, texelSize.y ), dp )\n\t\t\t) * ( 1.0 / 9.0 );\n\t\t#else\n\t\t\treturn texture2DCompare( shadowMap, cubeToUV( bd3D, texelSize.y ), dp );\n\t\t#endif\n\t}\n#endif\n";
+
+var shadowmap_pars_vertex = "#ifdef USE_SHADOWMAP\n\t#if NUM_DIR_LIGHTS > 0\n\t\tuniform mat4 directionalShadowMatrix[ NUM_DIR_LIGHTS ];\n\t\tvarying vec4 vDirectionalShadowCoord[ NUM_DIR_LIGHTS ];\n\t#endif\n\t#if NUM_SPOT_LIGHTS > 0\n\t\tuniform mat4 spotShadowMatrix[ NUM_SPOT_LIGHTS ];\n\t\tvarying vec4 vSpotShadowCoord[ NUM_SPOT_LIGHTS ];\n\t#endif\n\t#if NUM_POINT_LIGHTS > 0\n\t\tuniform mat4 pointShadowMatrix[ NUM_POINT_LIGHTS ];\n\t\tvarying vec4 vPointShadowCoord[ NUM_POINT_LIGHTS ];\n\t#endif\n#endif\n";
+
+var shadowmap_vertex = "#ifdef USE_SHADOWMAP\n\t#if NUM_DIR_LIGHTS > 0\n\tfor ( int i = 0; i < NUM_DIR_LIGHTS; i ++ ) {\n\t\tvDirectionalShadowCoord[ i ] = directionalShadowMatrix[ i ] * worldPosition;\n\t}\n\t#endif\n\t#if NUM_SPOT_LIGHTS > 0\n\tfor ( int i = 0; i < NUM_SPOT_LIGHTS; i ++ ) {\n\t\tvSpotShadowCoord[ i ] = spotShadowMatrix[ i ] * worldPosition;\n\t}\n\t#endif\n\t#if NUM_POINT_LIGHTS > 0\n\tfor ( int i = 0; i < NUM_POINT_LIGHTS; i ++ ) {\n\t\tvPointShadowCoord[ i ] = pointShadowMatrix[ i ] * worldPosition;\n\t}\n\t#endif\n#endif\n";
+
+var shadowmask_pars_fragment = "float getShadowMask() {\n\tfloat shadow = 1.0;\n\t#ifdef USE_SHADOWMAP\n\t#if NUM_DIR_LIGHTS > 0\n\tDirectionalLight directionalLight;\n\tfor ( int i = 0; i < NUM_DIR_LIGHTS; i ++ ) {\n\t\tdirectionalLight = directionalLights[ i ];\n\t\tshadow *= bool( directionalLight.shadow ) ? getShadow( directionalShadowMap[ i ], directionalLight.shadowMapSize, directionalLight.shadowBias, directionalLight.shadowRadius, vDirectionalShadowCoord[ i ] ) : 1.0;\n\t}\n\t#endif\n\t#if NUM_SPOT_LIGHTS > 0\n\tSpotLight spotLight;\n\tfor ( int i = 0; i < NUM_SPOT_LIGHTS; i ++ ) {\n\t\tspotLight = spotLights[ i ];\n\t\tshadow *= bool( spotLight.shadow ) ? getShadow( spotShadowMap[ i ], spotLight.shadowMapSize, spotLight.shadowBias, spotLight.shadowRadius, vSpotShadowCoord[ i ] ) : 1.0;\n\t}\n\t#endif\n\t#if NUM_POINT_LIGHTS > 0\n\tPointLight pointLight;\n\tfor ( int i = 0; i < NUM_POINT_LIGHTS; i ++ ) {\n\t\tpointLight = pointLights[ i ];\n\t\tshadow *= bool( pointLight.shadow ) ? getPointShadow( pointShadowMap[ i ], pointLight.shadowMapSize, pointLight.shadowBias, pointLight.shadowRadius, vPointShadowCoord[ i ], pointLight.shadowCameraNear, pointLight.shadowCameraFar ) : 1.0;\n\t}\n\t#endif\n\t#endif\n\treturn shadow;\n}\n";
+
+var skinbase_vertex = "#ifdef USE_SKINNING\n\tmat4 boneMatX = getBoneMatrix( skinIndex.x );\n\tmat4 boneMatY = getBoneMatrix( skinIndex.y );\n\tmat4 boneMatZ = getBoneMatrix( skinIndex.z );\n\tmat4 boneMatW = getBoneMatrix( skinIndex.w );\n#endif";
+
+var skinning_pars_vertex = "#ifdef USE_SKINNING\n\tuniform mat4 bindMatrix;\n\tuniform mat4 bindMatrixInverse;\n\t#ifdef BONE_TEXTURE\n\t\tuniform sampler2D boneTexture;\n\t\tuniform int boneTextureSize;\n\t\tmat4 getBoneMatrix( const in float i ) {\n\t\t\tfloat j = i * 4.0;\n\t\t\tfloat x = mod( j, float( boneTextureSize ) );\n\t\t\tfloat y = floor( j / float( boneTextureSize ) );\n\t\t\tfloat dx = 1.0 / float( boneTextureSize );\n\t\t\tfloat dy = 1.0 / float( boneTextureSize );\n\t\t\ty = dy * ( y + 0.5 );\n\t\t\tvec4 v1 = texture2D( boneTexture, vec2( dx * ( x + 0.5 ), y ) );\n\t\t\tvec4 v2 = texture2D( boneTexture, vec2( dx * ( x + 1.5 ), y ) );\n\t\t\tvec4 v3 = texture2D( boneTexture, vec2( dx * ( x + 2.5 ), y ) );\n\t\t\tvec4 v4 = texture2D( boneTexture, vec2( dx * ( x + 3.5 ), y ) );\n\t\t\tmat4 bone = mat4( v1, v2, v3, v4 );\n\t\t\treturn bone;\n\t\t}\n\t#else\n\t\tuniform mat4 boneMatrices[ MAX_BONES ];\n\t\tmat4 getBoneMatrix( const in float i ) {\n\t\t\tmat4 bone = boneMatrices[ int(i) ];\n\t\t\treturn bone;\n\t\t}\n\t#endif\n#endif\n";
+
+var skinning_vertex = "#ifdef USE_SKINNING\n\tvec4 skinVertex = bindMatrix * vec4( transformed, 1.0 );\n\tvec4 skinned = vec4( 0.0 );\n\tskinned += boneMatX * skinVertex * skinWeight.x;\n\tskinned += boneMatY * skinVertex * skinWeight.y;\n\tskinned += boneMatZ * skinVertex * skinWeight.z;\n\tskinned += boneMatW * skinVertex * skinWeight.w;\n\ttransformed = ( bindMatrixInverse * skinned ).xyz;\n#endif\n";
+
+var skinnormal_vertex = "#ifdef USE_SKINNING\n\tmat4 skinMatrix = mat4( 0.0 );\n\tskinMatrix += skinWeight.x * boneMatX;\n\tskinMatrix += skinWeight.y * boneMatY;\n\tskinMatrix += skinWeight.z * boneMatZ;\n\tskinMatrix += skinWeight.w * boneMatW;\n\tskinMatrix = bindMatrixInverse * skinMatrix * bindMatrix;\n\tobjectNormal = vec4( skinMatrix * vec4( objectNormal, 0.0 ) ).xyz;\n#endif\n";
+
+var specularmap_fragment = "float specularStrength;\n#ifdef USE_SPECULARMAP\n\tvec4 texelSpecular = texture2D( specularMap, vUv );\n\tspecularStrength = texelSpecular.r;\n#else\n\tspecularStrength = 1.0;\n#endif";
+
+var specularmap_pars_fragment = "#ifdef USE_SPECULARMAP\n\tuniform sampler2D specularMap;\n#endif";
+
+var tonemapping_fragment = "#if defined( TONE_MAPPING )\n gl_FragColor.rgb = toneMapping( gl_FragColor.rgb );\n#endif\n";
+
+var tonemapping_pars_fragment = "#ifndef saturate\n\t#define saturate(a) clamp( a, 0.0, 1.0 )\n#endif\nuniform float toneMappingExposure;\nuniform float toneMappingWhitePoint;\nvec3 LinearToneMapping( vec3 color ) {\n\treturn toneMappingExposure * color;\n}\nvec3 ReinhardToneMapping( vec3 color ) {\n\tcolor *= toneMappingExposure;\n\treturn saturate( color / ( vec3( 1.0 ) + color ) );\n}\n#define Uncharted2Helper( x ) max( ( ( x * ( 0.15 * x + 0.10 * 0.50 ) + 0.20 * 0.02 ) / ( x * ( 0.15 * x + 0.50 ) + 0.20 * 0.30 ) ) - 0.02 / 0.30, vec3( 0.0 ) )\nvec3 Uncharted2ToneMapping( vec3 color ) {\n\tcolor *= toneMappingExposure;\n\treturn saturate( Uncharted2Helper( color ) / Uncharted2Helper( vec3( toneMappingWhitePoint ) ) );\n}\nvec3 OptimizedCineonToneMapping( vec3 color ) {\n\tcolor *= toneMappingExposure;\n\tcolor = max( vec3( 0.0 ), color - 0.004 );\n\treturn pow( ( color * ( 6.2 * color + 0.5 ) ) / ( color * ( 6.2 * color + 1.7 ) + 0.06 ), vec3( 2.2 ) );\n}\n";
+
+var uv_pars_fragment = "#if defined( USE_MAP ) || defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( USE_SPECULARMAP ) || defined( USE_ALPHAMAP ) || defined( USE_EMISSIVEMAP ) || defined( USE_ROUGHNESSMAP ) || defined( USE_METALNESSMAP )\n\tvarying vec2 vUv;\n#endif";
+
+var uv_pars_vertex = "#if defined( USE_MAP ) || defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( USE_SPECULARMAP ) || defined( USE_ALPHAMAP ) || defined( USE_EMISSIVEMAP ) || defined( USE_ROUGHNESSMAP ) || defined( USE_METALNESSMAP )\n\tvarying vec2 vUv;\n\tuniform mat3 uvTransform;\n#endif\n";
+
+var uv_vertex = "#if defined( USE_MAP ) || defined( USE_BUMPMAP ) || defined( USE_NORMALMAP ) || defined( USE_SPECULARMAP ) || defined( USE_ALPHAMAP ) || defined( USE_EMISSIVEMAP ) || defined( USE_ROUGHNESSMAP ) || defined( USE_METALNESSMAP )\n\tvUv = ( uvTransform * vec3( uv, 1 ) ).xy;\n#endif";
+
+var uv2_pars_fragment = "#if defined( USE_LIGHTMAP ) || defined( USE_AOMAP )\n\tvarying vec2 vUv2;\n#endif";
+
+var uv2_pars_vertex = "#if defined( USE_LIGHTMAP ) || defined( USE_AOMAP )\n\tattribute vec2 uv2;\n\tvarying vec2 vUv2;\n#endif";
+
+var uv2_vertex = "#if defined( USE_LIGHTMAP ) || defined( USE_AOMAP )\n\tvUv2 = uv2;\n#endif";
+
+var worldpos_vertex = "#if defined( USE_ENVMAP ) || defined( DISTANCE ) || defined ( USE_SHADOWMAP )\n\tvec4 worldPosition = modelMatrix * vec4( transformed, 1.0 );\n#endif\n";
+
+var cube_frag = "uniform samplerCube tCube;\nuniform float tFlip;\nuniform float opacity;\nvarying vec3 vWorldPosition;\nvoid main() {\n\tgl_FragColor = textureCube( tCube, vec3( tFlip * vWorldPosition.x, vWorldPosition.yz ) );\n\tgl_FragColor.a *= opacity;\n}\n";
+
+var cube_vert = "varying vec3 vWorldPosition;\n#include \nvoid main() {\n\tvWorldPosition = transformDirection( position, modelMatrix );\n\t#include \n\t#include \n\tgl_Position.z = gl_Position.w;\n}\n";
+
+var depth_frag = "#if DEPTH_PACKING == 3200\n\tuniform float opacity;\n#endif\n#include \n#include \n#include \n#include \n#include \n#include \n#include \nvoid main() {\n\t#include \n\tvec4 diffuseColor = vec4( 1.0 );\n\t#if DEPTH_PACKING == 3200\n\t\tdiffuseColor.a = opacity;\n\t#endif\n\t#include \n\t#include \n\t#include \n\t#include \n\t#if DEPTH_PACKING == 3200\n\t\tgl_FragColor = vec4( vec3( gl_FragCoord.z ), opacity );\n\t#elif DEPTH_PACKING == 3201\n\t\tgl_FragColor = packDepthToRGBA( gl_FragCoord.z );\n\t#endif\n}\n";
+
+var depth_vert = "#include \n#include \n#include \n#include \n#include \n#include \n#include \nvoid main() {\n\t#include \n\t#include \n\t#ifdef USE_DISPLACEMENTMAP\n\t\t#include \n\t\t#include \n\t\t#include \n\t#endif\n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n}\n";
+
+var distanceRGBA_frag = "#define DISTANCE\nuniform vec3 referencePosition;\nuniform float nearDistance;\nuniform float farDistance;\nvarying vec3 vWorldPosition;\n#include \n#include \n#include \n#include \n#include \n#include \nvoid main () {\n\t#include \n\tvec4 diffuseColor = vec4( 1.0 );\n\t#include \n\t#include \n\t#include \n\tfloat dist = length( vWorldPosition - referencePosition );\n\tdist = ( dist - nearDistance ) / ( farDistance - nearDistance );\n\tdist = saturate( dist );\n\tgl_FragColor = packDepthToRGBA( dist );\n}\n";
+
+var distanceRGBA_vert = "#define DISTANCE\nvarying vec3 vWorldPosition;\n#include \n#include \n#include \n#include \n#include \n#include \nvoid main() {\n\t#include \n\t#include \n\t#ifdef USE_DISPLACEMENTMAP\n\t\t#include \n\t\t#include \n\t\t#include \n\t#endif\n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\tvWorldPosition = worldPosition.xyz;\n}\n";
+
+var equirect_frag = "uniform sampler2D tEquirect;\nvarying vec3 vWorldPosition;\n#include \nvoid main() {\n\tvec3 direction = normalize( vWorldPosition );\n\tvec2 sampleUV;\n\tsampleUV.y = asin( clamp( direction.y, - 1.0, 1.0 ) ) * RECIPROCAL_PI + 0.5;\n\tsampleUV.x = atan( direction.z, direction.x ) * RECIPROCAL_PI2 + 0.5;\n\tgl_FragColor = texture2D( tEquirect, sampleUV );\n}\n";
+
+var equirect_vert = "varying vec3 vWorldPosition;\n#include \nvoid main() {\n\tvWorldPosition = transformDirection( position, modelMatrix );\n\t#include \n\t#include \n}\n";
+
+var linedashed_frag = "uniform vec3 diffuse;\nuniform float opacity;\nuniform float dashSize;\nuniform float totalSize;\nvarying float vLineDistance;\n#include \n#include \n#include \n#include \n#include \nvoid main() {\n\t#include \n\tif ( mod( vLineDistance, totalSize ) > dashSize ) {\n\t\tdiscard;\n\t}\n\tvec3 outgoingLight = vec3( 0.0 );\n\tvec4 diffuseColor = vec4( diffuse, opacity );\n\t#include \n\t#include \n\toutgoingLight = diffuseColor.rgb;\n\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\n\t#include \n\t#include \n\t#include \n\t#include \n}\n";
+
+var linedashed_vert = "uniform float scale;\nattribute float lineDistance;\nvarying float vLineDistance;\n#include \n#include \n#include \n#include \n#include \nvoid main() {\n\t#include \n\tvLineDistance = scale * lineDistance;\n\tvec4 mvPosition = modelViewMatrix * vec4( position, 1.0 );\n\tgl_Position = projectionMatrix * mvPosition;\n\t#include \n\t#include \n\t#include \n}\n";
+
+var meshbasic_frag = "uniform vec3 diffuse;\nuniform float opacity;\n#ifndef FLAT_SHADED\n\tvarying vec3 vNormal;\n#endif\n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \nvoid main() {\n\t#include \n\tvec4 diffuseColor = vec4( diffuse, opacity );\n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\n\t#ifdef USE_LIGHTMAP\n\t\treflectedLight.indirectDiffuse += texture2D( lightMap, vUv2 ).xyz * lightMapIntensity;\n\t#else\n\t\treflectedLight.indirectDiffuse += vec3( 1.0 );\n\t#endif\n\t#include \n\treflectedLight.indirectDiffuse *= diffuseColor.rgb;\n\tvec3 outgoingLight = reflectedLight.indirectDiffuse;\n\t#include \n\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\n\t#include \n\t#include \n\t#include \n\t#include \n}\n";
+
+var meshbasic_vert = "#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \nvoid main() {\n\t#include \n\t#include \n\t#include \n\t#include \n\t#ifdef USE_ENVMAP\n\t#include \n\t#include \n\t#include \n\t#include \n\t#endif\n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n}\n";
+
+var meshlambert_frag = "uniform vec3 diffuse;\nuniform vec3 emissive;\nuniform float opacity;\nvarying vec3 vLightFront;\n#ifdef DOUBLE_SIDED\n\tvarying vec3 vLightBack;\n#endif\n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \nvoid main() {\n\t#include \n\tvec4 diffuseColor = vec4( diffuse, opacity );\n\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\n\tvec3 totalEmissiveRadiance = emissive;\n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\treflectedLight.indirectDiffuse = getAmbientLightIrradiance( ambientLightColor );\n\t#include \n\treflectedLight.indirectDiffuse *= BRDF_Diffuse_Lambert( diffuseColor.rgb );\n\t#ifdef DOUBLE_SIDED\n\t\treflectedLight.directDiffuse = ( gl_FrontFacing ) ? vLightFront : vLightBack;\n\t#else\n\t\treflectedLight.directDiffuse = vLightFront;\n\t#endif\n\treflectedLight.directDiffuse *= BRDF_Diffuse_Lambert( diffuseColor.rgb ) * getShadowMask();\n\t#include \n\tvec3 outgoingLight = reflectedLight.directDiffuse + reflectedLight.indirectDiffuse + totalEmissiveRadiance;\n\t#include \n\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n}\n";
+
+var meshlambert_vert = "#define LAMBERT\nvarying vec3 vLightFront;\n#ifdef DOUBLE_SIDED\n\tvarying vec3 vLightBack;\n#endif\n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \nvoid main() {\n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n}\n";
+
+var meshphong_frag = "#define PHONG\nuniform vec3 diffuse;\nuniform vec3 emissive;\nuniform vec3 specular;\nuniform float shininess;\nuniform float opacity;\n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \n#include \nvoid main() {\n\t#include \n\tvec4 diffuseColor = vec4( diffuse, opacity );\n\tReflectedLight reflectedLight = ReflectedLight( vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ), vec3( 0.0 ) );\n\tvec3 totalEmissiveRadiance = emissive;\n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\t#include \n\tvec3 outgoingLight = reflectedLight.directDiffuse + reflectedLight.indirectDiffuse + reflectedLight.directSpecular + reflectedLight.indirectSpecular + totalEmissiveRadiance;\n\t#include \n\tgl_FragColor = vec4( outgoingLight, diffuseColor.a );\n\t#include