Skip to content

Commit 7e26097

Browse files
author
Sylvain Bertrand
committed
Update code to RigidBodyTransform API changes
1 parent 259b6e1 commit 7e26097

File tree

90 files changed

+250
-250
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

90 files changed

+250
-250
lines changed

Atlas/src/us/ihmc/atlas/multisenseMocapExperiments/MultisenseHeadOnAStickManualTestMinimalNetworkProcessor.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -74,9 +74,9 @@ public void onNewMessage(PointCloud2 pointCloud)
7474
{
7575
UnpackedPointCloud pointCloudData = unpackPointsAndIntensities(pointCloud);
7676
Point3d[] points = pointCloudData.getPoints();
77-
orientationTransformFromLeftOpticalFrameToZUp.setEuler(-Math.PI/2, 0.0, -Math.PI/2);
77+
orientationTransformFromLeftOpticalFrameToZUp.setRotationEulerAndZeroTranslation(-Math.PI/2, 0.0, -Math.PI/2);
7878

79-
rpyCalibrationOffset.setEuler(Math.toRadians(-1.4), Math.toRadians(0.5), Math.toRadians(2.0));
79+
rpyCalibrationOffset.setRotationEulerAndZeroTranslation(Math.toRadians(-1.4), Math.toRadians(0.5), Math.toRadians(2.0));
8080
rpyCalibrationOffset.setTranslation(-0.005,-0.003,-0.003);
8181

8282
for(int i = 0; i < points.length; i++)

Atlas/src/us/ihmc/atlas/parameters/AtlasContactPointParameters.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -174,7 +174,7 @@ public void createHandKnobContactPoints()
174174
{
175175
RigidBodyTransform handContactPointTransform = new RigidBodyTransform();
176176

177-
handContactPointTransform.rotX(robotSide.negateIfRightSide(Math.PI / 2.0));
177+
handContactPointTransform.setRotationRollAndZeroTranslation(robotSide.negateIfRightSide(Math.PI / 2.0));
178178
handContactPointTransform.setTranslation(new Vector3d(0.0, robotSide.negateIfRightSide(0.13), robotSide.negateIfRightSide(0.01)));
179179
handContactPointTransforms.put(robotSide, handContactPointTransform);
180180
handContactPoints.put(robotSide, new ArrayList<Point2d>());

Atlas/src/us/ihmc/atlas/sensors/AtlasCollisionBoxProvider.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ public AtlasCollisionBoxProvider(JaxbSDFLoader loader, AtlasJointMap jointMap)
3232
// Add extra collision sphere around the knee, to avoid hitting points there on the real robot
3333
String kneeJoint = jointMap.getLegJointName(robotSide, LegJointName.KNEE);
3434
RigidBodyTransform kneePose = new RigidBodyTransform();
35-
kneePose.rotX(Math.PI / 2.0);
35+
kneePose.setRotationRollAndZeroTranslation(Math.PI / 2.0);
3636
kneePose.setTranslation(0.05, 0, 0.03);
3737
CollisionCylinder knee = new CollisionCylinder(kneePose, 0.11, 0.15 + 2.0 * extent);
3838
addCollisionShape(kneeJoint, knee);

Atlas/src/us/ihmc/atlas/sensors/VisionPoseEstimator.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -232,7 +232,7 @@ public void run()
232232
{
233233
RigidBodyTransform cameraToWorld = data.getRight();
234234
RigidBodyTransform opticalFrameToCameraFrame = new RigidBodyTransform();
235-
opticalFrameToCameraFrame.setEuler(-Math.PI / 2.0, 0.0, -Math.PI / 2);
235+
opticalFrameToCameraFrame.setRotationEulerAndZeroTranslation(-Math.PI / 2.0, 0.0, -Math.PI / 2);
236236
RigidBodyTransform targetToWorld = new RigidBodyTransform();
237237

238238
targetToWorld.multiply(cameraToWorld, opticalFrameToCameraFrame);

CommonWalkingControlModules/src/us/ihmc/commonWalkingControlModules/bipedSupportPolygons/ContactablePlaneBodyTools.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ public static RectangularContactableBody createTypicalContactablePlaneBodyForTes
1313
{
1414
RigidBodyTransform transform3D = new RigidBodyTransform();
1515
transform3D.setTranslation(0.1, 0.2, -0.5);
16-
transform3D.rotY(Math.PI / 2.0);
16+
transform3D.setRotationPitchAndZeroTranslation(Math.PI / 2.0);
1717

1818
ReferenceFrame soleFrame = ReferenceFrame.constructBodyFrameWithUnchangingTransformToParent(rigidBody.getName() + "SoleFrame", endEffectorFrame,
1919
transform3D);

CommonWalkingControlModules/src/us/ihmc/commonWalkingControlModules/desiredFootStep/HandstepHelper.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@ public static RigidBodyTransform computeHandstepTransform(boolean rotateZIntoX,
5353
if (rotateZIntoX)
5454
{
5555
RigidBodyTransform transformThree = new RigidBodyTransform();
56-
transformThree.rotY(Math.PI / 2.0);
56+
transformThree.setRotationPitchAndZeroTranslation(Math.PI / 2.0);
5757
transformOne.multiply(transformThree);
5858
}
5959

CommonWalkingControlModules/src/us/ihmc/commonWalkingControlModules/desiredHeadingAndVelocity/HeadingAndVelocityEvaluationScript.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -173,7 +173,7 @@ public void update(double time)
173173
Vector3d newDesiredVelocityDirection = new Vector3d(desiredHeading.getX(), desiredHeading.getY(), 0.0);
174174
newDesiredVelocityDirection.normalize(); // just to be sure
175175
RigidBodyTransform transform3D = new RigidBodyTransform();
176-
transform3D.rotZ(-Math.PI / 4.0);
176+
transform3D.setRotationYawAndZeroTranslation(-Math.PI / 4.0);
177177
transform3D.transform(newDesiredVelocityDirection);
178178

179179
desiredVelocityDirection.set(newDesiredVelocityDirection.getX(), newDesiredVelocityDirection.getY());
@@ -188,7 +188,7 @@ public void update(double time)
188188
Vector3d newDesiredVelocityDirection = new Vector3d(desiredHeading.getX(), desiredHeading.getY(), 0.0);
189189
newDesiredVelocityDirection.normalize(); // just to be sure
190190
RigidBodyTransform transform3D = new RigidBodyTransform();
191-
transform3D.rotZ(Math.PI / 4.0);
191+
transform3D.setRotationYawAndZeroTranslation(Math.PI / 4.0);
192192
transform3D.transform(newDesiredVelocityDirection);
193193

194194
desiredVelocityDirection.set(newDesiredVelocityDirection.getX(), newDesiredVelocityDirection.getY());

CommonWalkingControlModules/src/us/ihmc/commonWalkingControlModules/trajectories/CirclePoseTrajectoryGenerator.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -494,7 +494,7 @@ private void rotateInitialOrientation(FrameOrientation orientationToPack, double
494494
initialOrientation.changeFrame(circleFrame);
495495
orientationToPack.setIncludingFrame(initialOrientation);
496496

497-
axisRotationTransform.rotZ(angleFromInitialOrientation);
497+
axisRotationTransform.setRotationYawAndZeroTranslation(angleFromInitialOrientation);
498498

499499
orientationToPack.applyTransform(axisRotationTransform);
500500
}

CommonWalkingControlModules/src/us/ihmc/commonWalkingControlModules/visualizer/CommonInertiaEllipsoidsExampleSimulation.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ public static void main(String[] args)
4545

4646
System.out.println(momentOfInertia);
4747
RigidBodyTransform transform = new RigidBodyTransform();
48-
transform.rotX(-Math.PI / 2.0);
48+
transform.setRotationRollAndZeroTranslation(-Math.PI / 2.0);
4949
System.out.println(transform);
5050
momentOfInertia = InertiaTools.rotate(transform, momentOfInertia);
5151
System.out.println(momentOfInertia);

DarpaRoboticsChallenge/src/us/ihmc/darpaRoboticsChallenge/VehicleModelObjects.java

+10-10
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@ public VehicleModelObjects()
2424
double roll = 0.0;
2525
double pitch = 0.0;
2626
double yaw = 0.0;
27-
transform3D.setEuler(roll, pitch, yaw);
27+
transform3D.setRotationEulerAndZeroTranslation(roll, pitch, yaw);
2828

2929
Vector3d translation = new Vector3d(0.0, 0.0, 0.0);
3030
transform3D.setTranslationAndIdentityRotation(translation);
@@ -65,11 +65,11 @@ public VehicleModelObjects()
6565

6666
//Rotate to have the Z axis point out
6767
RigidBodyTransform finalAdjustment = new RigidBodyTransform();
68-
finalAdjustment.setEuler(0.0, Math.PI, 0.0);
68+
finalAdjustment.setRotationEulerAndZeroTranslation(0.0, Math.PI, 0.0);
6969
transform3D.multiply(finalAdjustment);
7070

7171
finalAdjustment = new RigidBodyTransform();
72-
finalAdjustment.setEuler(new Vector3d(0.0, 0.0, -Math.PI/2.0));
72+
finalAdjustment.setRotationEulerAndZeroTranslation(new Vector3d(0.0, 0.0, -Math.PI/2.0));
7373
transform3D.multiply(finalAdjustment);
7474

7575
objectTransforms.put(VehicleObject.GAS_PEDAL, transform3D);
@@ -107,11 +107,11 @@ public VehicleModelObjects()
107107

108108
//Rotate to have the Z axis point out
109109
RigidBodyTransform finalAdjustment = new RigidBodyTransform();
110-
finalAdjustment.setEuler(new Vector3d(0.0, Math.PI, 0.0));
110+
finalAdjustment.setRotationEulerAndZeroTranslation(new Vector3d(0.0, Math.PI, 0.0));
111111
transform3D.multiply(finalAdjustment);
112112

113113
finalAdjustment = new RigidBodyTransform();
114-
finalAdjustment.setEuler(new Vector3d(0.0, 0.0, -Math.PI/2.0));
114+
finalAdjustment.setRotationEulerAndZeroTranslation(new Vector3d(0.0, 0.0, -Math.PI/2.0));
115115
transform3D.multiply(finalAdjustment);
116116

117117
objectTransforms.put(VehicleObject.BRAKE_PEDAL, transform3D);
@@ -134,7 +134,7 @@ public VehicleModelObjects()
134134
RigidBodyTransform transform3D = new RigidBodyTransform(transform3DfromWorldToParent);
135135

136136
RigidBodyTransform finalAdjustment = new RigidBodyTransform();
137-
finalAdjustment.setEuler(new Vector3d(0.0, 0.0, -Math.PI/2.0));
137+
finalAdjustment.setRotationEulerAndZeroTranslation(new Vector3d(0.0, 0.0, -Math.PI/2.0));
138138
transform3D.multiply(finalAdjustment);
139139

140140
//transform to parent
@@ -241,11 +241,11 @@ public VehicleModelObjects()
241241

242242
//Rotate to have the Z axis point out
243243
RigidBodyTransform finalAdjustment = new RigidBodyTransform();
244-
finalAdjustment.setEuler(new Vector3d(0.0, -Math.PI/2.0, 0.0));
244+
finalAdjustment.setRotationEulerAndZeroTranslation(new Vector3d(0.0, -Math.PI/2.0, 0.0));
245245
transform3D.multiply(finalAdjustment);
246246

247247
finalAdjustment = new RigidBodyTransform();
248-
finalAdjustment.setEuler(new Vector3d(0.0, 0.0, -Math.PI/2.0));
248+
finalAdjustment.setRotationEulerAndZeroTranslation(new Vector3d(0.0, 0.0, -Math.PI/2.0));
249249
transform3D.multiply(finalAdjustment);
250250

251251
RigidBodyTransform adjustmentForSwitch = new RigidBodyTransform();
@@ -269,11 +269,11 @@ public VehicleModelObjects()
269269

270270
//Rotate to have the Z axis point out
271271
RigidBodyTransform finalAdjustment = new RigidBodyTransform();
272-
finalAdjustment.setEuler(new Vector3d(0.0, -Math.PI/2.0, 0.0));
272+
finalAdjustment.setRotationEulerAndZeroTranslation(new Vector3d(0.0, -Math.PI/2.0, 0.0));
273273
transform3D.multiply(finalAdjustment);
274274

275275
finalAdjustment = new RigidBodyTransform();
276-
finalAdjustment.setEuler(new Vector3d(0.0, 0.0, -Math.PI/2.0));
276+
finalAdjustment.setRotationEulerAndZeroTranslation(new Vector3d(0.0, 0.0, -Math.PI/2.0));
277277
transform3D.multiply(finalAdjustment);
278278

279279
RigidBodyTransform adjustmentForSwitch = new RigidBodyTransform();

DarpaRoboticsChallenge/src/us/ihmc/darpaRoboticsChallenge/environment/DRCDemo01NavigationEnvironment.java

+11-11
Original file line numberDiff line numberDiff line change
@@ -1373,7 +1373,7 @@ private static void setUpWall3D(CombinedTerrainObject3D combinedTerrainObject, d
13731373
double x = xy[0];
13741374
double y = xy[1];
13751375
RigidBodyTransform location = new RigidBodyTransform();
1376-
location.rotZ(Math.toRadians(yawDegrees));
1376+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
13771377

13781378
location.setTranslation(new Vector3d(x, y, height / 2));
13791379
RotatableBoxTerrainObject newBox = new RotatableBoxTerrainObject(new Box3d(location, length, width, height), app);
@@ -1386,7 +1386,7 @@ private static void setUpWall(CombinedTerrainObject3D combinedTerrainObject, dou
13861386
double x = xy[0];
13871387
double y = xy[1];
13881388
RigidBodyTransform location = new RigidBodyTransform();
1389-
location.rotZ(Math.toRadians(yawDegrees));
1389+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
13901390

13911391
location.setTranslation(new Vector3d(x, y, height / 2));
13921392
RotatableBoxTerrainObject newBox = new RotatableBoxTerrainObject(new Box3d(location, length, width, height), app);
@@ -1399,7 +1399,7 @@ private static void setUpFloatingStair(CombinedTerrainObject3D combinedTerrainOb
13991399
double xCenter = centerPoint[0];
14001400
double yCenter = centerPoint[1];
14011401
RigidBodyTransform location = new RigidBodyTransform();
1402-
location.rotZ(Math.toRadians(yawDegrees));
1402+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
14031403

14041404
location.setTranslation(new Vector3d(xCenter, yCenter, stairTopHeight - thickness / 2));
14051405
RotatableBoxTerrainObject newBox = new RotatableBoxTerrainObject(new Box3d(location, tread, width, thickness), app);
@@ -1459,7 +1459,7 @@ private static void setUpCinderBlock(CombinedTerrainObject3D combinedTerrainObje
14591459
double yCenter = centerPoint[1];
14601460

14611461
RigidBodyTransform location = new RigidBodyTransform();
1462-
location.rotZ(Math.toRadians(yawDegrees));
1462+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
14631463

14641464
location.setTranslation(new Vector3d(xCenter, yCenter, cinderBlockHeight / 2 + numberFlatSupports * cinderBlockHeight));
14651465
RotatableCinderBlockTerrainObject newBox = new RotatableCinderBlockTerrainObject(
@@ -1472,10 +1472,10 @@ private static void setUpSlopedBox(CombinedTerrainObject3D combinedTerrainObject
14721472
double yLength, double zLength, double slopeRadians, double yawDegrees, AppearanceDefinition app)
14731473
{
14741474
RigidBodyTransform location = new RigidBodyTransform();
1475-
location.rotZ(Math.toRadians(yawDegrees));
1475+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
14761476

14771477
RigidBodyTransform tilt = new RigidBodyTransform();
1478-
tilt.rotY(-slopeRadians);
1478+
tilt.setRotationPitchAndZeroTranslation(-slopeRadians);
14791479
location.multiply(tilt);
14801480

14811481
location.setTranslation(new Vector3d(xCenter, yCenter, zCenter));
@@ -1502,10 +1502,10 @@ private static void setUpSlopedCinderBlock(CombinedTerrainObject3D combinedTerra
15021502
AppearanceDefinition app = cinderBlockAppearance;
15031503

15041504
RigidBodyTransform location = new RigidBodyTransform();
1505-
location.rotZ(Math.toRadians(yawDegrees));
1505+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
15061506

15071507
RigidBodyTransform tilt = new RigidBodyTransform();
1508-
tilt.rotY(-cinderBlockTiltRadians);
1508+
tilt.setRotationPitchAndZeroTranslation(-cinderBlockTiltRadians);
15091509
location.multiply(tilt);
15101510

15111511
double zCenter = (cinderBlockHeight * Math.cos(cinderBlockTiltRadians) + cinderBlockLength * Math.sin(cinderBlockTiltRadians)) / 2;
@@ -1548,8 +1548,8 @@ private static void setUpCinderBlockUpright(CombinedTerrainObject3D combinedTerr
15481548
RigidBodyTransform location = new RigidBodyTransform();
15491549
RigidBodyTransform setUpright = new RigidBodyTransform();
15501550

1551-
location.rotZ(Math.toRadians(yawDegrees));
1552-
setUpright.rotX(Math.toRadians(90));
1551+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
1552+
setUpright.setRotationRollAndZeroTranslation(Math.toRadians(90));
15531553
location.multiply(setUpright);
15541554

15551555
location.setTranslation(new Vector3d(xCenter, yCenter, cinderBlockWidth / 2 + numberFlatSupports * cinderBlockHeight));
@@ -1575,7 +1575,7 @@ private static void setUpRampBlock(CombinedTerrainObject3D combinedTerrainObject
15751575
double rampRise = cinderBlockLength * Math.sin(cinderBlockTiltRadians);
15761576

15771577
RigidBodyTransform blockSupportLocation = new RigidBodyTransform();
1578-
blockSupportLocation.rotZ(Math.toRadians(yawDegrees));
1578+
blockSupportLocation.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
15791579
double[] xySupportRotatedOffset = rotateAroundOrigin(new double[] {(cinderBlockLength - rampRise) / 2, 0}, yawDegrees);
15801580
blockSupportLocation.setTranslation(
15811581
new Vector3d(xCenter + xySupportRotatedOffset[0], yCenter + xySupportRotatedOffset[1], rampRise / 2 + numberFlatSupports * cinderBlockHeight));

DarpaRoboticsChallenge/src/us/ihmc/darpaRoboticsChallenge/environment/DRCDemoEnvironmentWithBoxAndSteeringWheel.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,7 @@ private static void addContactableCylinderRobot(ArrayList<Robot> environmentRobo
8787
double z, double roll, double pitch, double yaw, double radius, double height)
8888
{
8989
RigidBodyTransform transform = new RigidBodyTransform();
90-
transform.setEuler(roll, pitch, yaw);
90+
transform.setRotationEulerAndZeroTranslation(roll, pitch, yaw);
9191

9292
Vector3d position = new Vector3d(x, y, z);
9393
Vector3d baseToCenter = new Vector3d(0.0, 0.0, -height / 2.0);
@@ -130,7 +130,7 @@ private CombinedTerrainObject3D createCombinedTerrainObject()
130130
private void addBox(double x, double y, double z, double roll, double pitch, double yaw, double sizeX, double sizeY, double sizeZ, CombinedTerrainObject3D terrainObject)
131131
{
132132
RigidBodyTransform transform = new RigidBodyTransform();
133-
transform.setEuler(roll, pitch, yaw);
133+
transform.setRotationEulerAndZeroTranslation(roll, pitch, yaw);
134134
transform.setTranslation(new Vector3d(x, y, z));
135135
Box3d box = new Box3d(transform, sizeX, sizeY, sizeZ);
136136
terrainObject.addRotatableBox(box, YoAppearance.DarkGray());

DarpaRoboticsChallenge/src/us/ihmc/darpaRoboticsChallenge/environment/DRCFinalsEnvironment.java

+4-4
Original file line numberDiff line numberDiff line change
@@ -293,7 +293,7 @@ private void setUpRampBlock(CombinedTerrainObject3D combinedTerrainObject, doubl
293293
double rampRise = cinderBlockLength * Math.sin(cinderBlockTiltRadians);
294294

295295
RigidBodyTransform blockSupportLocation = new RigidBodyTransform();
296-
blockSupportLocation.rotZ(Math.toRadians(yawDegrees));
296+
blockSupportLocation.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
297297
double[] xySupportRotatedOffset = rotateAroundOrigin(new double[] { (cinderBlockLength - rampRise) / 2, 0 }, yawDegrees);
298298
blockSupportLocation.setTranslation(new Vector3d(xCenter + xySupportRotatedOffset[0], yCenter + xySupportRotatedOffset[1], rampRise / 2
299299
+ numberFlatSupports * cinderBlockHeight));
@@ -316,10 +316,10 @@ private void setUpSlopedCinderBlock(CombinedTerrainObject3D combinedTerrainObjec
316316
AppearanceDefinition app = cinderBlockAppearance;
317317

318318
RigidBodyTransform location = new RigidBodyTransform();
319-
location.rotZ(Math.toRadians(yawDegrees));
319+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
320320

321321
RigidBodyTransform tilt = new RigidBodyTransform();
322-
tilt.rotY(-cinderBlockTiltRadians);
322+
tilt.setRotationPitchAndZeroTranslation(-cinderBlockTiltRadians);
323323
location.multiply(tilt);
324324

325325
double zCenter = (cinderBlockHeight * Math.cos(cinderBlockTiltRadians) + cinderBlockLength * Math.sin(cinderBlockTiltRadians)) / 2;
@@ -371,7 +371,7 @@ private void setUpCinderBlock(CombinedTerrainObject3D combinedTerrainObject, dou
371371
double yCenter = centerPoint[1];
372372

373373
RigidBodyTransform location = new RigidBodyTransform();
374-
location.rotZ(Math.toRadians(yawDegrees));
374+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
375375

376376
location.setTranslation(new Vector3d(xCenter, yCenter, cinderBlockHeight / 2 + numberFlatSupports * cinderBlockHeight));
377377
RotatableCinderBlockTerrainObject newBox = new RotatableCinderBlockTerrainObject(new Box3d(location, cinderBlockLength + overlapToPreventGaps,

DarpaRoboticsChallenge/src/us/ihmc/darpaRoboticsChallenge/environment/DRCStairsEnvironment.java

+3-3
Original file line numberDiff line numberDiff line change
@@ -140,7 +140,7 @@ private static void setUpFloatingStair(CombinedTerrainObject3D combinedTerrainOb
140140
double xCenter = centerPoint[0];
141141
double yCenter = centerPoint[1];
142142
RigidBodyTransform location = new RigidBodyTransform();
143-
location.rotZ(Math.toRadians(yawDegrees));
143+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
144144

145145
location.setTranslation(new Vector3d(xCenter, yCenter, stairTopHeight - thickness / 2));
146146
RotatableBoxTerrainObject newBox = new RotatableBoxTerrainObject(new Box3d(location, tread, width, thickness), app);
@@ -151,10 +151,10 @@ private static void setUpSlopedBox(CombinedTerrainObject3D combinedTerrainObject
151151
double yLength, double zLength, double slopeRadians, double yawDegrees, AppearanceDefinition app)
152152
{
153153
RigidBodyTransform location = new RigidBodyTransform();
154-
location.rotZ(Math.toRadians(yawDegrees));
154+
location.setRotationYawAndZeroTranslation(Math.toRadians(yawDegrees));
155155

156156
RigidBodyTransform tilt = new RigidBodyTransform();
157-
tilt.rotY(-slopeRadians);
157+
tilt.setRotationPitchAndZeroTranslation(-slopeRadians);
158158
location.multiply(tilt);
159159

160160
location.setTranslation(new Vector3d(xCenter, yCenter, zCenter));

DarpaRoboticsChallenge/src/us/ihmc/darpaRoboticsChallenge/lidarTests/IHMCMocapDataClient.java

+2-2
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ public void setupReferenceFrames()
3434
@Override
3535
protected void updateTransformToParent(RigidBodyTransform transformToParent)
3636
{
37-
transformToParent.setEuler(Math.toRadians(-90), Math.toRadians(0), Math.toRadians(0));
37+
transformToParent.setRotationEulerAndZeroTranslation(Math.toRadians(-90), Math.toRadians(0), Math.toRadians(0));
3838
}
3939
};
4040
mocapOriginFrame.update();
@@ -53,7 +53,7 @@ protected void updateTransformToParent(RigidBodyTransform transformToParent)
5353
@Override
5454
protected void updateTransformToParent(RigidBodyTransform transformToParent)
5555
{
56-
transformToParent.setEuler(Math.toRadians(90), 0, 0);
56+
transformToParent.setRotationEulerAndZeroTranslation(Math.toRadians(90), 0, 0);
5757
}
5858
};
5959
mocapRbZUpFrame.update();

DarpaRoboticsChallenge/src/us/ihmc/darpaRoboticsChallenge/networkProcessor/depthData/CarLocalizerTransformKeeper.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ public class CarLocalizerTransformKeeper
8383

8484
public void packTransformFromBasePelvisToWheel(RigidBodyTransform transformToPack)
8585
{
86-
transformFromOldBasePelvisToWheel.setEuler(WHEEL_FRAME_XX, WHEEL_FRAME_YY, WHEEL_FRAME_ZZ);
86+
transformFromOldBasePelvisToWheel.setRotationEulerAndZeroTranslation(WHEEL_FRAME_XX, WHEEL_FRAME_YY, WHEEL_FRAME_ZZ);
8787
transformFromOldBasePelvisToWheel.setTranslation(new Vector3d(WHEEL_FRAME_X, WHEEL_FRAME_Y, WHEEL_FRAME_Z));
8888
transformToPack.multiply(transformFromNewPelvisToOldPelvis, transformFromOldBasePelvisToWheel);
8989
}

0 commit comments

Comments
 (0)