Skip to content

Commit c515bda

Browse files
committed
refactor: address PR review feedback from maintainer
1 parent 622a2d8 commit c515bda

4 files changed

Lines changed: 70 additions & 44 deletions

File tree

javascript/README.md

Lines changed: 10 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -266,10 +266,10 @@ The type of joint. Can only be the URDF types of joints.
266266
### .limit
267267

268268
```js
269-
.limit : { lower : number, upper : number }
269+
.limit : { lower : number, upper : number, effort : number, velocity : number }
270270
```
271271

272-
An object containing the `lower` and `upper` constraints for the joint.
272+
An object containing the `lower` and `upper` position constraints, as well as the `effort` and `velocity` limits for the joint. All fields default to zero if not specified in the URDF.
273273

274274
### .axis
275275

@@ -357,6 +357,14 @@ name : string
357357

358358
The name of the link.
359359

360+
### .inertial
361+
362+
```js
363+
inertial : { mass : number, origin : { xyz : number[], rpy : number[] }, inertia : { ixx, ixy, ixz, iyy, iyz, izz : number } }
364+
```
365+
366+
The inertial properties of the link parsed from the `<inertial>` element. All fields default to zero if not specified in the URDF.
367+
360368
## URDFRobot
361369

362370
_extends [URDFLink](#URDFLink)_

javascript/src/URDFClasses.js

Lines changed: 23 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,28 @@ class URDFLink extends URDFBase {
6363
this.isURDFLink = true;
6464
this.type = 'URDFLink';
6565

66-
this.inertial = null;
66+
this.inertial = {
67+
mass: 0,
68+
origin: { xyz: [0, 0, 0], rpy: [0, 0, 0] },
69+
inertia: { ixx: 0, ixy: 0, ixz: 0, iyy: 0, iyz: 0, izz: 0 },
70+
};
71+
72+
}
73+
74+
copy(source, recursive) {
75+
76+
super.copy(source, recursive);
77+
78+
this.inertial = {
79+
mass: source.inertial.mass,
80+
origin: {
81+
xyz: [...source.inertial.origin.xyz],
82+
rpy: [...source.inertial.origin.rpy],
83+
},
84+
inertia: { ...source.inertial.inertia },
85+
};
86+
87+
return this;
6788

6889
}
6990

@@ -124,7 +145,7 @@ class URDFJoint extends URDFBase {
124145
this.jointValue = null;
125146
this.jointType = 'fixed';
126147
this.axis = new Vector3(1, 0, 0);
127-
this.limit = { lower: 0, upper: 0, effort: null, velocity: null };
148+
this.limit = { lower: 0, upper: 0, effort: 0, velocity: 0 };
128149
this.ignoreLimits = false;
129150

130151
this.origPosition = null;

javascript/src/URDFLoader.js

Lines changed: 28 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -37,14 +37,6 @@ function processTuple(val) {
3737

3838
}
3939

40-
// take a vector "x y z" and process it into
41-
// a THREE.Vector3
42-
function processVector(val) {
43-
44-
return new THREE.Vector3(...processTuple(val));
45-
46-
}
47-
4840
// applies a rotation a threejs object in URDF order
4941
function applyRotation(obj, rpy, additive = false) {
5042

@@ -413,35 +405,36 @@ class URDFLoader {
413405
target.urdfName = target.name;
414406
target.urdfNode = link;
415407

416-
// Extract the attributes
417-
children.forEach(n => {
408+
// Parse inertial properties
409+
const inertialNode = children.find(n => n.nodeName.toLowerCase() === 'inertial');
410+
if (inertialNode) {
418411

419-
const type = n.nodeName.toLowerCase();
420-
if (type === 'inertial') {
421-
const subNodes = [ ...n.children ];
422-
const origin = subNodes.find(sn => sn.nodeName.toLowerCase() === 'origin');
423-
const xyz = origin ? origin.getAttribute('xyz') : null;
424-
const rpy = origin ? origin.getAttribute('rpy') : null;
425-
const mass = subNodes.find(sn => sn.nodeName.toLowerCase() === 'mass');
426-
const inertia = subNodes.find(sn => sn.nodeName.toLowerCase() === 'inertia');
427-
target.inertial = origin || mass || inertia ? {
428-
origin: xyz || rpy ? {
429-
xyz: xyz ? processVector(xyz) : null,
430-
rpy: rpy ? processVector(rpy) : null,
431-
} : null,
432-
mass: mass ? parseFloat(mass.getAttribute('value') || 0) : null,
433-
inertia: inertia ? {
434-
ixx: parseFloat(inertia.getAttribute('ixx') || 0),
435-
ixy: parseFloat(inertia.getAttribute('ixy') || 0),
436-
ixz: parseFloat(inertia.getAttribute('ixz') || 0),
437-
iyy: parseFloat(inertia.getAttribute('iyy') || 0),
438-
iyz: parseFloat(inertia.getAttribute('iyz') || 0),
439-
izz: parseFloat(inertia.getAttribute('izz') || 0),
440-
} : null,
441-
} : null;
412+
[ ...inertialNode.children ].forEach(n => {
442413

443-
}
444-
});
414+
const type = n.nodeName.toLowerCase();
415+
if (type === 'origin') {
416+
417+
target.inertial.origin.xyz = processTuple(n.getAttribute('xyz'));
418+
target.inertial.origin.rpy = processTuple(n.getAttribute('rpy'));
419+
420+
} else if (type === 'mass') {
421+
422+
target.inertial.mass = parseFloat(n.getAttribute('value')) || 0;
423+
424+
} else if (type === 'inertia') {
425+
426+
target.inertial.inertia.ixx = parseFloat(n.getAttribute('ixx')) || 0;
427+
target.inertial.inertia.ixy = parseFloat(n.getAttribute('ixy')) || 0;
428+
target.inertial.inertia.ixz = parseFloat(n.getAttribute('ixz')) || 0;
429+
target.inertial.inertia.iyy = parseFloat(n.getAttribute('iyy')) || 0;
430+
target.inertial.inertia.iyz = parseFloat(n.getAttribute('iyz')) || 0;
431+
target.inertial.inertia.izz = parseFloat(n.getAttribute('izz')) || 0;
432+
433+
}
434+
435+
});
436+
437+
}
445438

446439
if (parseVisual) {
447440

javascript/test/URDFRobot.test.js

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -62,10 +62,10 @@ describe('URDFRobot', () => {
6262
expect(robot.joints.JOINT1.limit.upper).toEqual(3.14);
6363
expect(robot.joints.JOINT1.limit.velocity).toEqual(5.20);
6464

65-
expect(robot.joints.JOINT2.limit.effort).toEqual(null);
65+
expect(robot.joints.JOINT2.limit.effort).toEqual(0);
6666
expect(robot.joints.JOINT2.limit.lower).toEqual(0);
6767
expect(robot.joints.JOINT2.limit.upper).toEqual(0);
68-
expect(robot.joints.JOINT2.limit.velocity).toEqual(null);
68+
expect(robot.joints.JOINT2.limit.velocity).toEqual(0);
6969
});
7070

7171
it('should correctly parse joint inertial data.', () => {
@@ -94,8 +94,8 @@ describe('URDFRobot', () => {
9494
</robot>
9595
`);
9696

97-
expect(robot.links.LINK1.inertial.origin.rpy).toEqual(new Vector3(0, 0, -1.5707963267948966));
98-
expect(robot.links.LINK1.inertial.origin.xyz).toEqual(new Vector3(0.14635000035763, 0, 0));
97+
expect(robot.links.LINK1.inertial.origin.rpy).toEqual([0, 0, -1.5707963267948966]);
98+
expect(robot.links.LINK1.inertial.origin.xyz).toEqual([0.14635000035763, 0, 0]);
9999
expect(robot.links.LINK1.inertial.mass).toEqual(2.5076);
100100
expect(robot.links.LINK1.inertial.inertia.ixx).toEqual(0.00443333156);
101101
expect(robot.links.LINK1.inertial.inertia.iyy).toEqual(0.00443333156);
@@ -104,7 +104,11 @@ describe('URDFRobot', () => {
104104
expect(robot.links.LINK1.inertial.inertia.ixz).toEqual(0);
105105
expect(robot.links.LINK1.inertial.inertia.iyz).toEqual(0);
106106

107-
expect(robot.links.LINK2.inertial).toEqual(null);
107+
// LINK2 has no <inertial> tag — should still have default values
108+
expect(robot.links.LINK2.inertial.mass).toEqual(0);
109+
expect(robot.links.LINK2.inertial.origin.xyz).toEqual([0, 0, 0]);
110+
expect(robot.links.LINK2.inertial.origin.rpy).toEqual([0, 0, 0]);
111+
expect(robot.links.LINK2.inertial.inertia.ixx).toEqual(0);
108112
});
109113

110114
it('should parse material colors and name.', () => {

0 commit comments

Comments
 (0)