Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 10 additions & 2 deletions javascript/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -266,10 +266,10 @@ The type of joint. Can only be the URDF types of joints.
### .limit

```js
.limit : { lower : number, upper : number }
.limit : { lower : number, upper : number, effort : number, velocity : number }
```

An object containing the `lower` and `upper` constraints for the joint.
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.

### .axis

Expand Down Expand Up @@ -357,6 +357,14 @@ name : string

The name of the link.

### .inertial

```js
inertial : { mass : number, origin : { xyz : number[], rpy : number[] }, inertia : { ixx, ixy, ixz, iyy, iyz, izz : number } }
```

The inertial properties of the link parsed from the `<inertial>` element. All fields default to zero if not specified in the URDF.

## URDFRobot

_extends [URDFLink](#URDFLink)_
Expand Down
14 changes: 13 additions & 1 deletion javascript/src/URDFClasses.d.ts
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,21 @@ export class URDFVisual extends URDFBase {

}

export interface URDFInertial {

mass: number;
origin: { xyz: number[], rpy: number[] };
inertia: {
ixx: number; ixy: number; ixz: number;
iyy: number; iyz: number; izz: number;
};

}

export class URDFLink extends URDFBase {

isURDFLink: true;
inertial: URDFInertial;

}

Expand All @@ -34,7 +46,7 @@ export class URDFJoint extends URDFBase {
jointType: 'fixed' | 'continuous' | 'revolute' | 'planar' | 'prismatic' | 'floating';
angle: number;
jointValue: number[];
limit: { lower: number, upper: number }; // TODO: add more
limit: { lower: number, upper: number, effort: number, velocity: number };
ignoreLimits: boolean;
mimicJoints: URDFMimicJoint[];

Expand Down
27 changes: 26 additions & 1 deletion javascript/src/URDFClasses.js
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,29 @@ class URDFLink extends URDFBase {
this.isURDFLink = true;
this.type = 'URDFLink';

this.inertial = {
mass: 0,
origin: { xyz: [0, 0, 0], rpy: [0, 0, 0] },
inertia: { ixx: 0, ixy: 0, ixz: 0, iyy: 0, iyz: 0, izz: 0 },
};

}

copy(source, recursive) {

super.copy(source, recursive);

this.inertial = {
mass: source.inertial.mass,
origin: {
xyz: [...source.inertial.origin.xyz],
rpy: [...source.inertial.origin.rpy],
},
inertia: { ...source.inertial.inertia },
};

return this;

}

}
Expand Down Expand Up @@ -122,7 +145,7 @@ class URDFJoint extends URDFBase {
this.jointValue = null;
this.jointType = 'fixed';
this.axis = new Vector3(1, 0, 0);
this.limit = { lower: 0, upper: 0 };
this.limit = { lower: 0, upper: 0, effort: 0, velocity: 0 };
this.ignoreLimits = false;

this.origPosition = null;
Expand All @@ -141,6 +164,8 @@ class URDFJoint extends URDFBase {
this.axis = source.axis.clone();
this.limit.lower = source.limit.lower;
this.limit.upper = source.limit.upper;
this.limit.effort = source.limit.effort;
this.limit.velocity = source.limit.velocity;
this.ignoreLimits = false;

this.jointValue = [...source.jointValue];
Expand Down
33 changes: 33 additions & 0 deletions javascript/src/URDFLoader.js
Original file line number Diff line number Diff line change
Expand Up @@ -364,6 +364,8 @@ class URDFLoader {

obj.limit.lower = parseFloat(n.getAttribute('lower') || obj.limit.lower);
obj.limit.upper = parseFloat(n.getAttribute('upper') || obj.limit.upper);
obj.limit.effort = parseFloat(n.getAttribute('effort') || obj.limit.effort);
obj.limit.velocity = parseFloat(n.getAttribute('velocity') || obj.limit.velocity);

}
});
Expand Down Expand Up @@ -403,6 +405,37 @@ class URDFLoader {
target.urdfName = target.name;
target.urdfNode = link;

// Parse inertial properties
const inertialNode = children.find(n => n.nodeName.toLowerCase() === 'inertial');
if (inertialNode) {

[ ...inertialNode.children ].forEach(n => {

const type = n.nodeName.toLowerCase();
if (type === 'origin') {

target.inertial.origin.xyz = processTuple(n.getAttribute('xyz'));
target.inertial.origin.rpy = processTuple(n.getAttribute('rpy'));

} else if (type === 'mass') {

target.inertial.mass = parseFloat(n.getAttribute('value')) || 0;

} else if (type === 'inertia') {

target.inertial.inertia.ixx = parseFloat(n.getAttribute('ixx')) || 0;
target.inertial.inertia.ixy = parseFloat(n.getAttribute('ixy')) || 0;
target.inertial.inertia.ixz = parseFloat(n.getAttribute('ixz')) || 0;
target.inertial.inertia.iyy = parseFloat(n.getAttribute('iyy')) || 0;
target.inertial.inertia.iyz = parseFloat(n.getAttribute('iyz')) || 0;
target.inertial.inertia.izz = parseFloat(n.getAttribute('izz')) || 0;

}

});

}

if (parseVisual) {

const visualNodes = children.filter(n => n.nodeName.toLowerCase() === 'visual');
Expand Down
75 changes: 75 additions & 0 deletions javascript/test/URDFRobot.test.js
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,81 @@ describe('URDFRobot', () => {
expect(robot.joints.JOINT2.angle).toEqual(2);
});

it('should correctly parse joint efforts and velocities.', () => {
const loader = new URDFLoader();
const robot = loader.parse(`
<robot name="TEST">
<link name="LINK1"/>
<link name="LINK2"/>
<link name="LINK3"/>
<joint name="JOINT1" type="continuous">
<axis xyz="0 0 -1" />
<parent link="LINK1"/>
<child link="LINK2"/>
<limit effort="150" lower="-3.14" upper="3.14" velocity="5.20" />
</joint>
<joint name="JOINT2" type="continuous">
<axis xyz="0 0 -1" />
<parent link="LINK2"/>
<child link="LINK3"/>
</joint>
</robot>
`);

expect(robot.joints.JOINT1.limit.effort).toEqual(150);
expect(robot.joints.JOINT1.limit.lower).toEqual(-3.14);
expect(robot.joints.JOINT1.limit.upper).toEqual(3.14);
expect(robot.joints.JOINT1.limit.velocity).toEqual(5.20);

expect(robot.joints.JOINT2.limit.effort).toEqual(0);
expect(robot.joints.JOINT2.limit.lower).toEqual(0);
expect(robot.joints.JOINT2.limit.upper).toEqual(0);
expect(robot.joints.JOINT2.limit.velocity).toEqual(0);
});

it('should correctly parse joint inertial data.', () => {
const loader = new URDFLoader();
const robot = loader.parse(`
<robot name="TEST">
<link name="LINK1">
<inertial>
<origin rpy="0 0 -1.5707963267948966" xyz="0.14635000035763 0 0"/>
<mass value="2.5076"/>
<inertia ixx="0.00443333156" ixy="0.0" ixz="0.0" iyy="0.00443333156" iyz="0.0" izz="0.0072" />
</inertial>
</link>
<link name="LINK2"/>
<link name="LINK3"/>
<joint name="JOINT1" type="continuous">
<axis xyz="0 0 -1" />
<parent link="LINK1"/>
<child link="LINK2"/>
</joint>
<joint name="JOINT2" type="continuous">
<axis xyz="0 0 -1" />
<parent link="LINK2"/>
<child link="LINK3"/>
</joint>
</robot>
`);

expect(robot.links.LINK1.inertial.origin.rpy).toEqual([0, 0, -1.5707963267948966]);
expect(robot.links.LINK1.inertial.origin.xyz).toEqual([0.14635000035763, 0, 0]);
expect(robot.links.LINK1.inertial.mass).toEqual(2.5076);
expect(robot.links.LINK1.inertial.inertia.ixx).toEqual(0.00443333156);
expect(robot.links.LINK1.inertial.inertia.iyy).toEqual(0.00443333156);
expect(robot.links.LINK1.inertial.inertia.izz).toEqual(0.0072);
expect(robot.links.LINK1.inertial.inertia.ixy).toEqual(0);
expect(robot.links.LINK1.inertial.inertia.ixz).toEqual(0);
expect(robot.links.LINK1.inertial.inertia.iyz).toEqual(0);

// LINK2 has no <inertial> tag — should still have default values
expect(robot.links.LINK2.inertial.mass).toEqual(0);
expect(robot.links.LINK2.inertial.origin.xyz).toEqual([0, 0, 0]);
expect(robot.links.LINK2.inertial.origin.rpy).toEqual([0, 0, 0]);
expect(robot.links.LINK2.inertial.inertia.ixx).toEqual(0);
});

it('should parse material colors and name.', () => {
const loader = new URDFLoader();
const res = loader.parse(`
Expand Down
Loading