urdf-loader
Advanced tools
Comparing version 0.3.4 to 0.3.5
@@ -139,2 +139,4 @@ /* globals animToggle viewer setColor */ | ||
viewer.up = '+Z'; | ||
document.getElementById('up-select').value = viewer.up; | ||
viewer.urdf = | ||
@@ -141,0 +143,0 @@ filesNames |
@@ -167,13 +167,24 @@ /* globals animToggle viewer THREE */ | ||
// update the joint display | ||
const slider = li.querySelector('input[type="range"]'); | ||
const input = li.querySelector('input[type="number"]'); | ||
li.update = () => { | ||
let degVal = joint.urdf.type === 'revolute' ? joint.urdf.angle * RAD2DEG : joint.urdf.angle; | ||
if (Math.abs(degVal) > 1) degVal = degVal.toFixed(1); | ||
else degVal = degVal.toPrecision(2); | ||
let degVal = joint.urdf.angle; | ||
if (joint.urdf.type === 'revolute' || joint.urdf.type === 'continuous') { | ||
degVal *= RAD2DEG; | ||
} | ||
if (Math.abs(degVal) > 1) { | ||
degVal = degVal.toFixed(1); | ||
} else { | ||
degVal = degVal.toPrecision(2); | ||
} | ||
input.value = parseFloat(degVal); | ||
// directly input the value | ||
slider.value = joint.urdf.angle; | ||
if (viewer.ignoreLimits) { | ||
if (viewer.ignoreLimits || joint.urdf.type === 'continuous') { | ||
slider.min = -6.28; | ||
@@ -180,0 +191,0 @@ slider.max = 6.28; |
{ | ||
"name": "urdf-loader", | ||
"version": "0.3.4", | ||
"version": "0.3.5", | ||
"description": "URDF Loader for THREE.js and webcomponent viewer", | ||
@@ -5,0 +5,0 @@ "scripts": { |
@@ -16,4 +16,4 @@ # javascript urdf-loader [![npm version](https://badge.fury.io/js/urdf-loader.svg)](https://www.npmjs.com/package/urdf-loader) | ||
loader.load( | ||
'.../package/dir/', // URDF's package:// directory | ||
'T12/urdf/T12.URDF', // The path to the URDF in the package | ||
'.../package/dir/', // The equivelant of a (list of) ROS package(s):// directory | ||
'T12/urdf/T12.URDF', // The path to the URDF within the package OR absolute | ||
robot => { }, // The robot is loaded! | ||
@@ -25,2 +25,6 @@ (path, ext, done) => { }, // Callback for each mesh for custom mesh processing and loading code | ||
### Limitations | ||
- Only `prismatic`, `continuous`, `revolute`, and `fixed` joints are supported. | ||
- Collision tags are not parsed. | ||
### API | ||
@@ -43,6 +47,15 @@ #### URDFLoader(manager) | ||
The path representing the `package://` directory to load `package://` relative files. | ||
The path representing the `package://` directory(s) to load `package://` relative files. | ||
##### urdfpath | ||
If the argument is a string, then it is used to replace the `package://` prefix when loading geometry. To specify multiple packages an object syntax used defining the package name to the package path: | ||
```js | ||
{ | ||
"package1": ".../path/to/package1", | ||
"package2": ".../path/to/package2", | ||
... | ||
} | ||
``` | ||
##### urdf | ||
_required_ | ||
@@ -89,4 +102,31 @@ | ||
Corresponds to the `package` parameter in `URDFLoader.load`. | ||
Corresponds to the `package` parameter in `URDFLoader.load`. Supported are: | ||
1. Single package: | ||
```html | ||
// 1. Example for single package named `default_package` | ||
<urdf-viewer package=".../path/to/default_package" ...></urdf-viewer> | ||
``` | ||
Fallback within 1: If the target package within the `package://` relative files do not match the default path it is assumed that the default path is the parent folder that contains the target package(s). | ||
```html | ||
// 1. Example for single package named `default_package` with fallback: | ||
<urdf-viewer package=".../path/to/parent" ...></urdf-viewer> | ||
// since `parent` does not match `default_package` | ||
// the path ".../path/to/parent/default_package" is assumed | ||
``` | ||
2. Serialized package map: | ||
E.g. if the meshes of a URDF are distributed over mutliple packages. | ||
```html | ||
// 2. Example for serialized package map that contains `package1` and `package2` | ||
<urdf-viewer package="package1:.../path/to/package1, package2:.../path/to/package1" ...></urdf-viewer> | ||
``` | ||
#### urdf | ||
@@ -93,0 +133,0 @@ |
@@ -261,3 +261,3 @@ /* globals URDFViewer THREE */ | ||
let hovered = null; | ||
el.addEventListener('mousemove', e => { | ||
this._mouseMoveFunc = e => { | ||
@@ -340,6 +340,6 @@ toMouseCoord(e, mouse); | ||
}, true); | ||
}; | ||
// Clean up | ||
el.addEventListener('mouseup', e => { | ||
this._mouseUpFunc = e => { | ||
@@ -354,6 +354,22 @@ if (dragging) { | ||
}); | ||
}; | ||
} | ||
connectedCallback() { | ||
super.connectedCallback(); | ||
window.addEventListener('mousemove', this._mouseMoveFunc, true); | ||
window.addEventListener('mouseup', this._mouseUpFunc, true); | ||
} | ||
disconnectedCallback() { | ||
super.disconnectedCallback(); | ||
window.removeEventListener('mousemove', this._mouseMoveFunc, true); | ||
window.removeEventListener('mouseup', this._mouseUpFunc, true); | ||
} | ||
attributeChangedCallback(attr, oldval, newval) { | ||
@@ -360,0 +376,0 @@ |
@@ -66,2 +66,3 @@ /* globals THREE URDFLoader */ | ||
this._dirty = false; | ||
this._loadScheduled = false; | ||
this.robot = null; | ||
@@ -215,3 +216,3 @@ | ||
this._loadUrdf(this.package, this.urdf); | ||
this._scheduleLoad(); | ||
break; | ||
@@ -337,25 +338,39 @@ | ||
// Watch the package and urdf field and load the | ||
_loadUrdf(pkg, urdf) { | ||
_scheduleLoad() { | ||
const _dispose = item => { | ||
// if our current model is already what's being requested | ||
// or has been loaded then early out | ||
if (this._prevload === `${ this.package }|${ this.urdf }`) return; | ||
this._prevload = `${ this.package }|${ this.urdf }`; | ||
if (!item) return; | ||
if (item.parent) item.parent.remove(item); | ||
if (item.dispose) item.dispose(); | ||
item.children.forEach(c => _dispose(c)); | ||
// if we're already waiting on a load then early out | ||
if (this._loadScheduled) return; | ||
this._loadScheduled = true; | ||
}; | ||
if (this.robot) { | ||
if (this._prevload === `${ pkg }|${ urdf }`) return; | ||
this.robot.traverse(c => c.dispose && c.dispose()); | ||
this.robot.parent.remove(this.robot); | ||
this.robot = null; | ||
_dispose(this.robot); | ||
this.robot = null; | ||
} | ||
requestAnimationFrame(() => { | ||
this._loadUrdf(this.package, this.urdf); | ||
this._loadScheduled = false; | ||
}); | ||
} | ||
// Watch the package and urdf field and load the robot model. | ||
// This should _only_ be called from _scheduleLoad because that | ||
// ensures the that current robot has been removed | ||
_loadUrdf(pkg, urdf) { | ||
this.dispatchEvent(new CustomEvent('urdf-change', { bubbles: true, cancelable: true, composed: true })); | ||
if (pkg && urdf) { | ||
if (urdf) { | ||
this._prevload = `${ pkg }|${ urdf }`; | ||
// Keep track of this request and make | ||
@@ -411,2 +426,20 @@ // sure it doesn't get overwritten by | ||
let meshesLoaded = 0; | ||
if (pkg.includes(':') && (pkg.split(':')[1].substring(0, 2)) !== '//') { | ||
// E.g. pkg = "pkg_name: path/to/pkg_name, pk2: path2/to/pk2"} | ||
// Convert pkg(s) into a map. E.g. | ||
// { "pkg_name": "path/to/pkg_name", | ||
// "pk2": "path2/to/pk2" } | ||
pkg = pkg.split(',').reduce(function(map, value) { | ||
const [pkgName, pkgPath] = value.split(/:(.+)/).filter(x => !!x); | ||
map[pkgName.trim()] = pkgPath.trim(); | ||
return map; | ||
}, {}); | ||
} | ||
this.urdfLoader.load( | ||
@@ -423,3 +456,3 @@ pkg, | ||
_dispose(robot); | ||
robot.traverse(c => c.dispose && c.dispose()); | ||
return; | ||
@@ -429,3 +462,3 @@ | ||
requestAnimationFrame(() => updateMaterials(robot)); | ||
updateMaterials(robot); | ||
@@ -439,2 +472,4 @@ this.robot = robot; | ||
this._dirty = true; | ||
}, | ||
@@ -441,0 +476,0 @@ |
@@ -90,4 +90,4 @@ /* globals THREE */ | ||
/* Public API */ | ||
// pkg: The equivelant of a ROS package:// directory | ||
// urdf: The URDF path in the directory | ||
// pkg: The equivelant of a (list of) ROS package(s):// directory | ||
// urdf: The path to the URDF within the package OR absolute | ||
// cb: Callback that is passed the model once loaded | ||
@@ -98,3 +98,6 @@ load(pkg, urdf, cb, loadMeshCb, fetchOptions) { | ||
// prepending the package info | ||
let path = urdf; | ||
// If path is relative | ||
if (!/^[^:]+:\/\//.test(path)) { | ||
@@ -148,2 +151,40 @@ | ||
/* Private Functions */ | ||
// Resolves the path of mesh files | ||
_resolveMeshPath(pkg, meshPath) { | ||
if (!/^package:\/\//.test(meshPath)) return meshPath; | ||
// Remove "package://" keyword and split meshPath at the first slash | ||
const [targetPkg, relPath] = meshPath.replace(/^package:\/\//, '').split(/\/(.+)/); | ||
if (typeof pkg === 'string') { | ||
// "pkg" is one single package | ||
if (pkg.endsWith(targetPkg)) { | ||
// "pkg" is the target package | ||
return pkg + '/' + relPath; | ||
} else { | ||
// Assume "pkg" is the target package's parent directory | ||
return pkg + '/' + targetPkg + '/' + relPath; | ||
} | ||
} else if (typeof pkg === 'object') { | ||
// "pkg" is a map of packages | ||
if (targetPkg in pkg) { | ||
return pkg[targetPkg] + '/' + relPath; | ||
} else { | ||
console.warn(`Error: ${ targetPkg } not found in provided pkgs!`); | ||
} | ||
} | ||
} | ||
// Process the URDF text format | ||
@@ -371,2 +412,3 @@ _processUrdf(pkg, data, loadMeshCb) { | ||
const material = new THREE.MeshPhongMaterial(); | ||
let primitiveModel = null; | ||
this.forEach(vn.children, n => { | ||
@@ -380,4 +422,4 @@ | ||
const filename = n.children[0].getAttribute('filename').replace(/^package:\/\//, ''); | ||
const path = pkg + '/' + filename; | ||
const filename = n.children[0].getAttribute('filename'); | ||
const path = this._resolveMeshPath(pkg, filename); | ||
const ext = path.match(/.*\.([A-Z0-9]+)$/i).pop() || ''; | ||
@@ -410,58 +452,40 @@ const scaleAttr = n.children[0].getAttribute('scale'); | ||
// TODO: We use animation frames here to ensure that materials are | ||
// appropriately applied. It would be better to scrape up all the data | ||
// before adding it to the scene | ||
requestAnimationFrame(() => { | ||
primitiveModel = new THREE.Mesh(); | ||
primitiveModel.geometry = new THREE.BoxGeometry(1, 1, 1); | ||
primitiveModel.material = material; | ||
const mesh = new THREE.Mesh(); | ||
mesh.geometry = new THREE.BoxGeometry(1, 1, 1); | ||
mesh.material = material; | ||
const size = this._processTuple(n.children[0].getAttribute('size')); | ||
const size = this._processTuple(n.children[0].getAttribute('size')); | ||
linkObj.add(primitiveModel); | ||
primitiveModel.scale.set(size[0], size[1], size[2]); | ||
linkObj.add(mesh); | ||
this._applyRotation(mesh, rpy); | ||
mesh.position.set(xyz[0], xyz[1], xyz[2]); | ||
mesh.scale.set(size[0], size[1], size[2]); | ||
}); | ||
} else if (geoType === 'sphere') { | ||
requestAnimationFrame(() => { | ||
primitiveModel = new THREE.Mesh(); | ||
primitiveModel.geometry = new THREE.SphereGeometry(1, 30, 30); | ||
primitiveModel.material = material; | ||
const mesh = new THREE.Mesh(); | ||
mesh.geometry = new THREE.SphereGeometry(1, 30, 30); | ||
mesh.material = material; | ||
const radius = parseFloat(n.children[0].getAttribute('radius')) || 0; | ||
primitiveModel.scale.set(radius, radius, radius); | ||
const radius = parseFloat(n.children[0].getAttribute('radius')) || 0; | ||
mesh.position.set(xyz[0], xyz[1], xyz[2]); | ||
mesh.scale.set(radius, radius, radius); | ||
linkObj.add(primitiveModel); | ||
linkObj.add(mesh); | ||
}); | ||
} else if (geoType === 'cylinder') { | ||
requestAnimationFrame(() => { | ||
const radius = parseFloat(n.children[0].getAttribute('radius')) || 0; | ||
const length = parseFloat(n.children[0].getAttribute('length')) || 0; | ||
const radius = parseFloat(n.children[0].getAttribute('radius')) || 0; | ||
const length = parseFloat(n.children[0].getAttribute('length')) || 0; | ||
primitiveModel = new THREE.Object3D(); | ||
const mesh = new THREE.Mesh(); | ||
mesh.geometry = new THREE.CylinderBufferGeometry(1, 1, 1, 30); | ||
mesh.material = material; | ||
mesh.scale.set(radius, length, radius); | ||
const mesh = new THREE.Mesh(); | ||
mesh.geometry = new THREE.CylinderBufferGeometry(1, 1, 1, 30); | ||
mesh.material = material; | ||
mesh.scale.set(radius, length, radius); | ||
primitiveModel.add(mesh); | ||
mesh.rotation.set(Math.PI / 2, 0, 0); | ||
const obj = new THREE.Object3D(); | ||
obj.add(mesh); | ||
mesh.rotation.set(Math.PI / 2, 0, 0); | ||
linkObj.add(primitiveModel); | ||
this._applyRotation(primitiveModel, rpy); | ||
primitiveModel.position.set(xyz[0], xyz[1], xyz[2]); | ||
linkObj.add(obj); | ||
this._applyRotation(obj, rpy); | ||
obj.position.set(xyz[0], xyz[1], xyz[2]); | ||
}); | ||
} | ||
@@ -505,4 +529,14 @@ | ||
// apply the position and rotation to the primitive geometry after | ||
// the fact because it's guaranteed to have been scraped from the child | ||
// nodes by this point | ||
if (primitiveModel) { | ||
this._applyRotation(primitiveModel, rpy); | ||
primitiveModel.position.set(xyz[0], xyz[1], xyz[2]); | ||
} | ||
} | ||
}; |
Sorry, the diff of this file is too big to display
Sorry, the diff of this file is not supported yet
License Policy Violation
LicenseThis package is not allowed per your license policy. Review the package's license to ensure compliance.
Found 1 instance in 1 package
License Policy Violation
LicenseThis package is not allowed per your license policy. Review the package's license to ensure compliance.
Found 1 instance in 1 package
2746211
17
7911
221