@@ -94,17 +94,12 @@ void InsertSDFExtensionJoint(tinyxml2::XMLElement *_elem,
94
94
// / option is set
95
95
bool FixedJointShouldBeReduced (urdf::JointSharedPtr _jnt);
96
96
97
- // / reduced fixed joints: apply transform reduction for ray sensors
97
+ // / reduced fixed joints: apply transform reduction for named elements
98
98
// / in extensions when doing fixed joint reduction
99
- void ReduceSDFExtensionSensorTransformReduction (
99
+ void ReduceSDFExtensionElementTransformReduction (
100
100
std::vector<XMLDocumentPtr>::iterator _blobIt,
101
- gz::math::Pose3d _reductionTransform);
102
-
103
- // / reduced fixed joints: apply transform reduction for projectors in
104
- // / extensions when doing fixed joint reduction
105
- void ReduceSDFExtensionProjectorTransformReduction (
106
- std::vector<XMLDocumentPtr>::iterator _blobIt,
107
- gz::math::Pose3d _reductionTransform);
101
+ const gz::math::Pose3d &_reductionTransform,
102
+ const std::string &_elementName);
108
103
109
104
110
105
// / reduced fixed joints: apply transform reduction to extensions
@@ -412,8 +407,8 @@ void ReduceVisualToParent(urdf::LinkSharedPtr _parentLink,
412
407
// collision elements of the child link into the parent link
413
408
void ReduceFixedJoints (tinyxml2::XMLElement *_root, urdf::LinkSharedPtr _link)
414
409
{
415
- // if child is attached to self by fixed _link first go up the tree,
416
- // check it's children recursively
410
+ // if child is attached to self by fixed joint first go up the tree,
411
+ // check its children recursively
417
412
for (unsigned int i = 0 ; i < _link->child_links .size () ; ++i)
418
413
{
419
414
if (FixedJointShouldBeReduced (_link->child_links [i]->parent_joint ))
@@ -2482,8 +2477,7 @@ void ReduceSDFExtensionToParent(urdf::LinkSharedPtr _link)
2482
2477
for (std::vector<SDFExtensionPtr>::iterator ge = ext->second .begin ();
2483
2478
ge != ext->second .end (); ++ge)
2484
2479
{
2485
- (*ge)->reductionTransform = TransformToParentFrame (
2486
- (*ge)->reductionTransform ,
2480
+ (*ge)->reductionTransform = CopyPose (
2487
2481
_link->parent_joint ->parent_to_joint_origin_transform );
2488
2482
// for sensor and projector blocks only
2489
2483
ReduceSDFExtensionsTransform ((*ge));
@@ -2571,11 +2565,12 @@ void ReduceSDFExtensionsTransform(SDFExtensionPtr _ge)
2571
2565
for (auto blobIt = _ge->blobs .begin ();
2572
2566
blobIt != _ge->blobs .end (); ++blobIt)
2573
2567
{
2574
- // / @todo make sure we are not missing any additional transform reductions
2575
- ReduceSDFExtensionSensorTransformReduction (blobIt,
2576
- _ge->reductionTransform );
2577
- ReduceSDFExtensionProjectorTransformReduction (blobIt,
2578
- _ge->reductionTransform );
2568
+ ReduceSDFExtensionElementTransformReduction (
2569
+ blobIt, _ge->reductionTransform , " light" );
2570
+ ReduceSDFExtensionElementTransformReduction (
2571
+ blobIt, _ge->reductionTransform , " projector" );
2572
+ ReduceSDFExtensionElementTransformReduction (
2573
+ blobIt, _ge->reductionTransform , " sensor" );
2579
2574
}
2580
2575
}
2581
2576
@@ -3366,12 +3361,13 @@ bool FixedJointShouldBeReduced(urdf::JointSharedPtr _jnt)
3366
3361
}
3367
3362
3368
3363
// //////////////////////////////////////////////////////////////////////////////
3369
- void ReduceSDFExtensionSensorTransformReduction (
3364
+ void ReduceSDFExtensionElementTransformReduction (
3370
3365
std::vector<XMLDocumentPtr>::iterator _blobIt,
3371
- gz::math::Pose3d _reductionTransform)
3366
+ const gz::math::Pose3d &_reductionTransform,
3367
+ const std::string &_elementName)
3372
3368
{
3373
- auto sensorElement = (*_blobIt)->FirstChildElement ();
3374
- if ( strcmp (sensorElement ->Name (), " sensor " ) == 0 )
3369
+ auto element = (*_blobIt)->FirstChildElement ();
3370
+ if ( strcmp (element ->Name (), _elementName. c_str () ) == 0 )
3375
3371
{
3376
3372
// parse it and add/replace the reduction transform
3377
3373
// find first instance of xyz and rpy, replace with reduction transform
@@ -3385,166 +3381,51 @@ void ReduceSDFExtensionSensorTransformReduction(
3385
3381
// sdfdbg << " " << streamIn.CStr() << "\n";
3386
3382
// }
3387
3383
3388
- auto sensorPose {gz::math::Pose3d::Zero};
3384
+ auto pose {gz::math::Pose3d::Zero};
3389
3385
{
3390
- auto sensorPosText = " 0 0 0 0 0 0" ;
3391
- const auto & oldPoseKey = sensorElement->FirstChildElement (" pose" );
3386
+ std::string poseText = " 0 0 0 0 0 0" ;
3387
+
3388
+ const auto & oldPoseKey = element->FirstChildElement (" pose" );
3392
3389
if (oldPoseKey)
3393
3390
{
3394
3391
const auto & poseElemXml = oldPoseKey->ToElement ();
3395
3392
if (poseElemXml->Attribute (" relative_to" ))
3396
- return ;
3397
-
3398
- // see below for explanation; if a sibling element exists, it stores the
3399
- // original <sensor><pose> tag content
3400
- const auto & sibling = sensorElement->NextSibling ();
3401
- if (poseElemXml->GetText () && !sibling)
3402
- sensorPosText = poseElemXml->GetText ();
3403
- else if (sibling && sibling->ToElement ()->GetText ())
3404
- sensorPosText = sibling->ToElement ()->GetText ();
3405
- else
3406
3393
{
3407
- sdferr << " Unexpected case in sensor pose computation\n " ;
3408
3394
return ;
3409
3395
}
3410
3396
3411
- // delete the <pose> tag, we'll add a new one at the end
3412
- sensorElement->DeleteChild (oldPoseKey);
3413
- }
3414
-
3415
- // parse the 6-tuple text into math::Pose3d
3416
- std::stringstream ss;
3417
- ss.imbue (std::locale::classic ());
3418
- ss << sensorPosText;
3419
- ss >> sensorPose;
3420
- if (ss.fail ())
3421
- {
3422
- sdferr << " Could not parse <sensor><pose>: [" << sensorPosText << " ]\n " ;
3423
- return ;
3424
- }
3425
-
3426
- // critical part: we store the original <pose> tag from <sensor> actually
3427
- // as a sibling of <sensor>... only first element of the blob is processed
3428
- // further, so its siblings can be used as temporary storage; we store the
3429
- // original <pose> tag there so that we can use the <sensor><pose> tag
3430
- // for storing the reduced position
3431
- auto doc = (*_blobIt)->GetDocument ();
3432
- const auto & poseTxt = doc->NewText (sensorPosText);
3433
- auto poseKey = doc->NewElement (" pose" );
3434
- poseKey->LinkEndChild (poseTxt);
3435
- (*_blobIt)->LinkEndChild (poseKey);
3436
- }
3437
-
3438
- _reductionTransform = _reductionTransform * sensorPose;
3439
-
3440
- // convert reductionTransform to values
3441
- urdf::Vector3 reductionXyz (_reductionTransform.Pos ().X (),
3442
- _reductionTransform.Pos ().Y (),
3443
- _reductionTransform.Pos ().Z ());
3444
- urdf::Rotation reductionQ (_reductionTransform.Rot ().X (),
3445
- _reductionTransform.Rot ().Y (),
3446
- _reductionTransform.Rot ().Z (),
3447
- _reductionTransform.Rot ().W ());
3448
-
3449
- urdf::Vector3 reductionRpy;
3450
- reductionQ.getRPY (reductionRpy.x , reductionRpy.y , reductionRpy.z );
3451
-
3452
- // output updated pose to text
3453
- std::ostringstream poseStream;
3454
- poseStream << reductionXyz.x << " " << reductionXyz.y
3455
- << " " << reductionXyz.z << " " << reductionRpy.x
3456
- << " " << reductionRpy.y << " " << reductionRpy.z ;
3457
-
3458
- auto * doc = (*_blobIt)->GetDocument ();
3459
- tinyxml2::XMLText *poseTxt = doc->NewText (poseStream.str ().c_str ());
3460
- tinyxml2::XMLElement *poseKey = doc->NewElement (" pose" );
3461
-
3462
- poseKey->LinkEndChild (poseTxt);
3463
-
3464
- sensorElement->LinkEndChild (poseKey);
3465
- }
3466
- }
3467
-
3468
- // //////////////////////////////////////////////////////////////////////////////
3469
- void ReduceSDFExtensionProjectorTransformReduction (
3470
- std::vector<XMLDocumentPtr>::iterator _blobIt,
3471
- gz::math::Pose3d _reductionTransform)
3472
- {
3473
- auto projectorElement = (*_blobIt)->FirstChildElement ();
3474
- if ( strcmp (projectorElement->Name (), " projector" ) == 0 )
3475
- {
3476
- // parse it and add/replace the reduction transform
3477
- // find first instance of xyz and rpy, replace with reduction transform
3478
- //
3479
- // for (tinyxml2::XMLNode* elIt = (*_blobIt)->FirstChildElement();
3480
- // elIt; elIt = elIt->NextSibling())
3481
- // {
3482
- // std::ostringstream streamIn;
3483
- // streamIn << *elIt;
3484
- // sdfdbg << " " << streamIn << "\n";
3485
- // }
3486
-
3487
- auto projectorPose {gz::math::Pose3d::Zero};
3488
- {
3489
- auto projectorPosText = " 0 0 0 0 0 0" ;
3490
- const auto & oldPoseKey = projectorElement->FirstChildElement (" pose" );
3491
- if (oldPoseKey)
3492
- {
3493
- const auto & poseElemXml = oldPoseKey->ToElement ();
3494
- if (poseElemXml->Attribute (" relative_to" ))
3495
- return ;
3496
-
3497
- // see below for explanation; if a sibling element exists, it stores the
3498
- // original <projector><pose> tag content
3499
- const auto & sibling = projectorElement->NextSibling ();
3500
- if (poseElemXml->GetText () && !sibling)
3501
- projectorPosText = poseElemXml->GetText ();
3502
- else if (sibling && sibling->ToElement ()->GetText ())
3503
- projectorPosText = sibling->ToElement ()->GetText ();
3504
- else
3397
+ if (poseElemXml->GetText ())
3505
3398
{
3506
- sdferr << " Unexpected case in projector pose computation\n " ;
3507
- return ;
3399
+ poseText = poseElemXml->GetText ();
3508
3400
}
3509
3401
3510
3402
// delete the <pose> tag, we'll add a new one at the end
3511
- projectorElement ->DeleteChild (oldPoseKey);
3403
+ element ->DeleteChild (oldPoseKey);
3512
3404
}
3513
3405
3514
3406
// parse the 6-tuple text into math::Pose3d
3515
- std::stringstream ss;
3407
+ std::stringstream ss;
3516
3408
ss.imbue (std::locale::classic ());
3517
- ss << projectorPosText ;
3518
- ss >> projectorPose ;
3409
+ ss << poseText ;
3410
+ ss >> pose ;
3519
3411
if (ss.fail ())
3520
3412
{
3521
- sdferr << " Could not parse <projector ><pose>: ["
3522
- << projectorPosText << " ]\n " ;
3413
+ sdferr << " Could not parse <" << _elementName << " ><pose>: ["
3414
+ << poseText << " ]\n " ;
3523
3415
return ;
3524
3416
}
3525
-
3526
- // critical part: we store the original <pose> tag from <projector>
3527
- // actually as a sibling of <projector>... only first element of the blob
3528
- // is processed further, so its siblings can be used as temporary storage;
3529
- // we store the original <pose> tag there so that we can use the
3530
- // <projector><pose> tag for storing the reduced position
3531
- auto doc = (*_blobIt)->GetDocument ();
3532
- const auto & poseTxt = doc->NewText (projectorPosText);
3533
- auto poseKey = doc->NewElement (" pose" );
3534
- poseKey->LinkEndChild (poseTxt);
3535
- (*_blobIt)->LinkEndChild (poseKey);
3536
3417
}
3537
3418
3538
- _reductionTransform = _reductionTransform * projectorPose ;
3419
+ pose = _reductionTransform * pose ;
3539
3420
3540
3421
// convert reductionTransform to values
3541
- urdf::Vector3 reductionXyz (_reductionTransform .Pos ().X (),
3542
- _reductionTransform .Pos ().Y (),
3543
- _reductionTransform .Pos ().Z ());
3544
- urdf::Rotation reductionQ (_reductionTransform .Rot ().X (),
3545
- _reductionTransform .Rot ().Y (),
3546
- _reductionTransform .Rot ().Z (),
3547
- _reductionTransform .Rot ().W ());
3422
+ urdf::Vector3 reductionXyz (pose .Pos ().X (),
3423
+ pose .Pos ().Y (),
3424
+ pose .Pos ().Z ());
3425
+ urdf::Rotation reductionQ (pose .Rot ().X (),
3426
+ pose .Rot ().Y (),
3427
+ pose .Rot ().Z (),
3428
+ pose .Rot ().W ());
3548
3429
3549
3430
urdf::Vector3 reductionRpy;
3550
3431
reductionQ.getRPY (reductionRpy.x , reductionRpy.y , reductionRpy.z );
@@ -3557,10 +3438,11 @@ void ReduceSDFExtensionProjectorTransformReduction(
3557
3438
3558
3439
auto * doc = (*_blobIt)->GetDocument ();
3559
3440
tinyxml2::XMLText *poseTxt = doc->NewText (poseStream.str ().c_str ());
3560
- auto poseKey = doc->NewElement (" pose" );
3441
+ tinyxml2::XMLElement *poseKey = doc->NewElement (" pose" );
3442
+
3561
3443
poseKey->LinkEndChild (poseTxt);
3562
3444
3563
- projectorElement ->LinkEndChild (poseKey);
3445
+ element ->LinkEndChild (poseKey);
3564
3446
}
3565
3447
}
3566
3448
0 commit comments