-
Notifications
You must be signed in to change notification settings - Fork 96
/
parser_urdf.cc
3840 lines (3472 loc) · 129 KB
/
parser_urdf.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* Copyright 2012 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#include <algorithm>
#include <fstream>
#include <map>
#include <memory>
#include <set>
#include <sstream>
#include <string>
#include <utility>
#include <vector>
#include <gz/math/Helpers.hh>
#include <gz/math/Pose3.hh>
#include <gz/math/Quaternion.hh>
#include <gz/math/Vector3.hh>
#include <urdf_model/model.h>
#include <urdf_model/link.h>
#include <urdf_parser/urdf_parser.h>
#include "sdf/Error.hh"
#include "sdf/sdf.hh"
#include "sdf/Types.hh"
#include "XmlUtils.hh"
#include "SDFExtension.hh"
#include "parser_urdf.hh"
using namespace sdf;
namespace sdf {
inline namespace SDF_VERSION_NAMESPACE {
using XMLDocumentPtr = std::shared_ptr<tinyxml2::XMLDocument>;
using XMLElementPtr = std::shared_ptr<tinyxml2::XMLElement>;
typedef std::shared_ptr<SDFExtension> SDFExtensionPtr;
typedef std::map<std::string, std::vector<SDFExtensionPtr> >
StringSDFExtensionPtrMap;
/// create SDF geometry block based on URDF
StringSDFExtensionPtrMap g_extensions;
bool g_reduceFixedJoints;
bool g_enforceLimits;
const char kCollisionExt[] = "_collision";
const char kVisualExt[] = "_visual";
const char kLumpPrefix[] = "_fixed_joint_lump__";
urdf::Pose g_initialRobotPose;
bool g_initialRobotPoseValid = false;
std::set<std::string> g_fixedJointsTransformedInRevoluteJoints;
std::set<std::string> g_fixedJointsTransformedInFixedJoints;
const int g_outputDecimalPrecision = 16;
const char kSdformatUrdfExtensionUrl[] =
"http://sdformat.org/tutorials?tut=sdformat_urdf_extensions";
/// \brief parser xml string into urdf::Vector3
/// \param[in] _key XML key where vector3 value might be
/// \param[in] _scale scalar scale for the vector3
/// \return a urdf::Vector3
urdf::Vector3 ParseVector3(tinyxml2::XMLNode *_key, double _scale = 1.0);
urdf::Vector3 ParseVector3(const std::string &_str, double _scale = 1.0);
/// insert extensions into collision geoms
void InsertSDFExtensionCollision(tinyxml2::XMLElement *_elem,
const std::string &_linkName);
/// insert extensions into model
void InsertSDFExtensionRobot(tinyxml2::XMLElement *_elem);
/// insert extensions into visuals
void InsertSDFExtensionVisual(tinyxml2::XMLElement *_elem,
const std::string &_linkName);
/// insert extensions into joints
void InsertSDFExtensionJoint(tinyxml2::XMLElement *_elem,
const std::string &_jointName);
/// reduced fixed joints: check if a fixed joint should be lumped
/// checking both the joint type and if disabledFixedJointLumping
/// option is set
bool FixedJointShouldBeReduced(urdf::JointSharedPtr _jnt);
/// reduced fixed joints: apply transform reduction for named elements
/// in extensions when doing fixed joint reduction
void ReduceSDFExtensionElementTransformReduction(
std::vector<XMLDocumentPtr>::iterator _blobIt,
const gz::math::Pose3d &_reductionTransform,
const std::string &_elementName);
/// reduced fixed joints: apply transform reduction to extensions
/// when doing fixed joint reduction
void ReduceSDFExtensionsTransform(SDFExtensionPtr _ge);
/// reduce fixed joints: lump joints to parent link
void ReduceJointsToParent(urdf::LinkSharedPtr _link);
/// reduce fixed joints: lump collisions to parent link
void ReduceCollisionsToParent(urdf::LinkSharedPtr _link);
/// reduce fixed joints: lump visuals to parent link
void ReduceVisualsToParent(urdf::LinkSharedPtr _link);
/// reduce fixed joints: lump inertial to parent link
void ReduceInertialToParent(urdf::LinkSharedPtr /*_link*/);
/// create SDF Collision block based on URDF
void CreateCollision(tinyxml2::XMLElement* _elem,
urdf::LinkConstSharedPtr _link,
urdf::CollisionSharedPtr _collision,
const std::string &_oldLinkName = std::string(""));
/// create SDF Visual block based on URDF
void CreateVisual(tinyxml2::XMLElement *_elem, urdf::LinkConstSharedPtr _link,
urdf::VisualSharedPtr _visual,
const std::string &_oldLinkName = std::string(""));
/// create SDF Joint block based on URDF
void CreateJoint(tinyxml2::XMLElement *_root, urdf::LinkConstSharedPtr _link,
const gz::math::Pose3d &_currentTransform);
/// insert extensions into links
void InsertSDFExtensionLink(tinyxml2::XMLElement *_elem,
const std::string &_linkName);
/// create visual blocks from urdf visuals
void CreateVisuals(tinyxml2::XMLElement* _elem, urdf::LinkConstSharedPtr _link);
/// create collision blocks from urdf collisions
void CreateCollisions(tinyxml2::XMLElement* _elem,
urdf::LinkConstSharedPtr _link);
/// create SDF Inertial block based on URDF
void CreateInertial(tinyxml2::XMLElement *_elem,
urdf::LinkConstSharedPtr _link);
/// append transform (pose) to the end of the xml element
void AddTransform(tinyxml2::XMLElement *_elem,
const gz::math::Pose3d &_transform);
/// create SDF from URDF link
void CreateSDF(tinyxml2::XMLElement *_root, urdf::LinkConstSharedPtr _link);
/// create SDF Link block based on URDF
void CreateLink(tinyxml2::XMLElement *_root, urdf::LinkConstSharedPtr _link,
const gz::math::Pose3d &_currentTransform);
/// reduced fixed joints: apply appropriate frame updates in joint
/// inside urdf extensions when doing fixed joint reduction
void ReduceSDFExtensionJointFrameReplace(
tinyxml2::XMLElement *_blob,
urdf::LinkSharedPtr _link);
/// reduced fixed joints: apply appropriate frame updates in gripper
/// inside urdf extensions when doing fixed joint reduction
void ReduceSDFExtensionGripperFrameReplace(
std::vector<XMLDocumentPtr>::iterator _blobIt,
urdf::LinkSharedPtr _link);
/// reduced fixed joints: apply appropriate frame updates in projector
/// inside urdf extensions when doing fixed joint reduction
void ReduceSDFExtensionProjectorFrameReplace(
std::vector<XMLDocumentPtr>::iterator _blobIt,
urdf::LinkSharedPtr _link);
/// reduced fixed joints: apply appropriate frame updates in plugins
/// inside urdf extensions when doing fixed joint reduction
void ReduceSDFExtensionPluginFrameReplace(
tinyxml2::XMLElement *_blob,
urdf::LinkSharedPtr _link, const std::string &_pluginName,
const std::string &_elementName,
gz::math::Pose3d _reductionTransform);
/// reduced fixed joints: apply appropriate frame updates in urdf
/// extensions when doing fixed joint reduction
void ReduceSDFExtensionContactSensorFrameReplace(
std::vector<XMLDocumentPtr>::iterator _blobIt,
urdf::LinkSharedPtr _link);
/// \brief reduced fixed joints: apply appropriate updates to urdf
/// extensions when doing fixed joint reduction
///
/// Take the link's existing list of gazebo extensions, transfer them
/// into parent link. Along the way, update local transforms by adding
/// the additional transform to parent. Also, look through all
/// referenced link names with plugins and update references to current
/// link to the parent link. (ReduceSDFExtensionFrameReplace())
///
/// \param[in] _link pointer to urdf link, its extensions will be reduced
void ReduceSDFExtensionToParent(urdf::LinkSharedPtr _link);
/// reduced fixed joints: apply appropriate frame updates
/// in urdf extensions when doing fixed joint reduction
void ReduceSDFExtensionFrameReplace(SDFExtensionPtr _ge,
urdf::LinkSharedPtr _link);
/// get value from <key value="..."/> pair and return it as string
std::string GetKeyValueAsString(tinyxml2::XMLElement* _elem);
/// \brief append key value pair to the end of the xml element
/// \param[in] _elem pointer to xml element
/// \param[in] _key string containing key to add to xml element
/// \param[in] _value string containing value for the key added
void AddKeyValue(tinyxml2::XMLElement *_elem, const std::string &_key,
const std::string &_value);
/// \brief convert values to string
/// \param[in] _count number of values in _values array
/// \param[in] _values array of double values
/// \return a string
std::string Values2str(unsigned int _count, const double *_values);
void CreateGeometry(tinyxml2::XMLElement *_elem,
urdf::GeometrySharedPtr _geometry);
/// reduced fixed joints: transform to parent frame
urdf::Pose TransformToParentFrame(urdf::Pose _transformInLinkFrame,
urdf::Pose _parentToLinkTransform);
/// reduced fixed joints: transform to parent frame
gz::math::Pose3d TransformToParentFrame(
gz::math::Pose3d _transformInLinkFrame,
urdf::Pose _parentToLinkTransform);
/// reduced fixed joints: transform to parent frame
gz::math::Pose3d TransformToParentFrame(
gz::math::Pose3d _transformInLinkFrame,
gz::math::Pose3d _parentToLinkTransform);
/// reduced fixed joints: utility to copy between urdf::Pose and
/// math::Pose
gz::math::Pose3d CopyPose(urdf::Pose _pose);
/// reduced fixed joints: utility to copy between urdf::Pose and
/// math::Pose
urdf::Pose CopyPose(gz::math::Pose3d _pose);
////////////////////////////////////////////////////////////////////////////////
bool URDF2SDF::IsURDF(const std::string &_filename)
{
tinyxml2::XMLDocument xmlDoc;
if (tinyxml2::XML_SUCCESS == xmlDoc.LoadFile(_filename.c_str()))
{
tinyxml2::XMLPrinter printer;
xmlDoc.Print(&printer);
std::string urdfStr = printer.CStr();
urdf::ModelInterfaceSharedPtr robotModel = urdf::parseURDF(urdfStr);
return robotModel != nullptr;
}
return false;
}
/////////////////////////////////////////////////
urdf::Vector3 ParseVector3(const std::string &_str, double _scale)
{
std::vector<std::string> pieces = sdf::split(_str, " ");
std::vector<double> vals;
for (unsigned int i = 0; i < pieces.size(); ++i)
{
if (pieces[i] != "")
{
try
{
vals.push_back(_scale * std::stod(pieces[i]));
}
catch(std::invalid_argument &)
{
sdferr << "xml key [" << _str
<< "][" << i << "] value [" << pieces[i]
<< "] is not a valid double from a 3-tuple\n";
return urdf::Vector3(0, 0, 0);
}
}
}
if (vals.size() == 3)
{
return urdf::Vector3(vals[0], vals[1], vals[2]);
}
else
{
return urdf::Vector3(0, 0, 0);
}
}
/////////////////////////////////////////////////
urdf::Vector3 ParseVector3(tinyxml2::XMLNode *_key, double _scale)
{
if (_key != nullptr)
{
tinyxml2::XMLElement *key = _key->ToElement();
if (key != nullptr)
{
return ParseVector3(GetKeyValueAsString(key), _scale);
}
sdferr << "key[" << _key->Value() << "] does not contain a Vector3\n";
}
else
{
sdferr << "Pointer to XML node _key is nullptr\n";
}
return urdf::Vector3(0, 0, 0);
}
/////////////////////////////////////////////////
/// \brief convert Vector3 to string
/// \param[in] _vector a urdf::Vector3
/// \return a string
std::string Vector32Str(const urdf::Vector3 _vector)
{
std::stringstream ss;
ss << _vector.x;
ss << " ";
ss << _vector.y;
ss << " ";
ss << _vector.z;
return ss.str();
}
////////////////////////////////////////////////////////////////////////////////
/// \brief Check and add collision to parent link
/// \param[in] _parentLink destination for _collision
/// \param[in] _name urdfdom 0.3+: urdf collision group name with lumped
/// collision info (see ReduceCollisionsToParent).
/// urdfdom 0.2: collision name with lumped
/// collision info (see ReduceCollisionsToParent).
/// \param[in] _collision move this collision to _parentLink
void ReduceCollisionToParent(urdf::LinkSharedPtr _parentLink,
const std::string &_name,
urdf::CollisionSharedPtr _collision)
{
// added a check to see if _collision already exist in
// _parentLink::collision_array if not, add it.
_collision->name = _name;
std::vector<urdf::CollisionSharedPtr>::iterator collisionIt =
find(_parentLink->collision_array.begin(),
_parentLink->collision_array.end(),
_collision);
if (collisionIt != _parentLink->collision_array.end())
{
sdfwarn << "attempted to add collision [" << _collision->name
<< "] to link ["
<< _parentLink->name
<< "], but it already exists in collision_array under name ["
<< (*collisionIt)->name << "]\n";
}
else
{
_parentLink->collision_array.push_back(_collision);
}
}
////////////////////////////////////////////////////////////////////////////////
/// \brief Check and add visual to parent link
/// \param[in] _parentLink destination for _visual
/// \param[in] _name urdfdom 0.3+: urdf visual group name with lumped
/// visual info (see ReduceVisualsToParent).
/// urdfdom 0.2: visual name with lumped
/// visual info (see ReduceVisualsToParent).
/// \param[in] _visual move this visual to _parentLink
void ReduceVisualToParent(urdf::LinkSharedPtr _parentLink,
const std::string &_name,
urdf::VisualSharedPtr _visual)
{
// added a check to see if _visual already exist in
// _parentLink::visual_array if not, add it.
_visual->name = _name;
std::vector<urdf::VisualSharedPtr>::iterator visualIt =
find(_parentLink->visual_array.begin(),
_parentLink->visual_array.end(),
_visual);
if (visualIt != _parentLink->visual_array.end())
{
sdfwarn << "attempted to add visual [" << _visual->name
<< "] to link ["
<< _parentLink->name
<< "], but it already exists in visual_array under name ["
<< (*visualIt)->name << "]\n";
}
else
{
_parentLink->visual_array.push_back(_visual);
}
}
////////////////////////////////////////////////////////////////////////////////
/// reduce fixed joints by lumping inertial, visual and
// collision elements of the child link into the parent link
void ReduceFixedJoints(tinyxml2::XMLElement *_root, urdf::LinkSharedPtr _link)
{
// if child is attached to self by fixed joint first go up the tree,
// check its children recursively
for (unsigned int i = 0 ; i < _link->child_links.size() ; ++i)
{
if (FixedJointShouldBeReduced(_link->child_links[i]->parent_joint))
{
ReduceFixedJoints(_root, _link->child_links[i]);
}
}
// reduce this _link's stuff up the tree to parent but skip first joint
// if it's the world
if (_link->getParent() && _link->getParent()->name != "world" &&
_link->parent_joint && FixedJointShouldBeReduced(_link->parent_joint) )
{
sdfdbg << "Fixed Joint Reduction: extension lumping from ["
<< _link->name << "] to [" << _link->getParent()->name << "]\n";
// Add //model/frame tag to memorialize reduced joint
sdf::Frame jointFrame;
jointFrame.SetName(_link->parent_joint->name);
jointFrame.SetAttachedTo(_link->getParent()->name);
jointFrame.SetRawPose(
CopyPose(_link->parent_joint->parent_to_joint_origin_transform));
// Add //model/frame tag to memorialize reduced link
sdf::Frame linkFrame;
linkFrame.SetName(_link->name);
linkFrame.SetAttachedTo(_link->parent_joint->name);
// Serialize sdf::Frame objects to xml and add to SDFExtension
SDFExtensionPtr sdfExt = std::make_shared<SDFExtension>();
auto sdfFrameToExtension = [&sdfExt](const sdf::Frame &_frame)
{
XMLDocumentPtr xmlNewDoc = std::make_shared<tinyxml2::XMLDocument>();
sdf::PrintConfig config;
config.SetOutPrecision(16);
xmlNewDoc->Parse(_frame.ToElement()->ToString("", config).c_str());
if (xmlNewDoc->Error())
{
sdferr << "Error while parsing serialized frames: "
<< xmlNewDoc->ErrorStr() << '\n';
}
sdfExt->blobs.push_back(xmlNewDoc);
};
sdfFrameToExtension(jointFrame);
sdfFrameToExtension(linkFrame);
// Add //frame tags to model extension vector
g_extensions[""].push_back(sdfExt);
// lump sdf extensions to parent, (give them new reference _link names)
ReduceSDFExtensionToParent(_link);
// reduce _link elements to parent
ReduceInertialToParent(_link);
ReduceVisualsToParent(_link);
ReduceCollisionsToParent(_link);
ReduceJointsToParent(_link);
}
// continue down the tree for non-fixed joints
for (unsigned int i = 0 ; i < _link->child_links.size() ; ++i)
{
if (!FixedJointShouldBeReduced(_link->child_links[i]->parent_joint))
{
ReduceFixedJoints(_root, _link->child_links[i]);
}
}
}
// ODE dMatrix
typedef double dMatrix3[4*3];
typedef double dVector3[4];
#define _R(i, j) R[(i)*4+(j)]
#define _I(i, j) I[(i)*4+(j)]
#define dRecip(x) ((1.0f/(x)))
struct dMass;
void dMassSetZero(dMass *m);
void dMassSetParameters(dMass *m, double themass,
double cgx, double cgy, double cgz,
double I11, double I22, double I33,
double I12, double I13, double I23);
struct dMass
{
double mass;
dVector3 c;
dMatrix3 I;
dMass()
{
dMassSetZero(this);
}
void setZero()
{
dMassSetZero(this);
}
void setParameters(double themass, double cgx, double cgy, double cgz,
double I11, double I22, double I33,
double I12, double I13, double I23)
{
dMassSetParameters(this,
themass,
cgx,
cgy,
cgz,
I11,
I22,
I33,
I12,
I13,
I23);
}
};
void dSetZero(double *a, int n)
{
// dAASSERT (a && n >= 0);
double *acurr = a;
int ncurr = n;
while (ncurr > 0)
{
*(acurr++) = 0;
--ncurr;
}
}
void dMassSetZero(dMass *m)
{
// dAASSERT (m);
m->mass = 0.0;
dSetZero(m->c, sizeof(m->c) / sizeof(m->c[0]));
dSetZero(m->I, sizeof(m->I) / sizeof(m->I[0]));
}
void dMassSetParameters(dMass *m, double themass,
double cgx, double cgy, double cgz,
double I11, double I22, double I33,
double I12, double I13, double I23)
{
// dAASSERT (m);
dMassSetZero(m);
m->mass = themass;
m->c[0] = cgx;
m->c[1] = cgy;
m->c[2] = cgz;
m->_I(0, 0) = I11;
m->_I(1, 1) = I22;
m->_I(2, 2) = I33;
m->_I(0, 1) = I12;
m->_I(0, 2) = I13;
m->_I(1, 2) = I23;
m->_I(1, 0) = I12;
m->_I(2, 0) = I13;
m->_I(2, 1) = I23;
// dMassCheck (m);
}
void dRFromEulerAngles(dMatrix3 R, double phi, double theta, double psi)
{
double sphi, cphi, stheta, ctheta, spsi, cpsi;
// dAASSERT (R);
sphi = sin(phi);
cphi = cos(phi);
stheta = sin(theta);
ctheta = cos(theta);
spsi = sin(psi);
cpsi = cos(psi);
_R(0, 0) = cpsi*ctheta;
_R(0, 1) = spsi*ctheta;
_R(0, 2) =-stheta;
_R(0, 3) = 0.0;
_R(1, 0) = cpsi*stheta*sphi - spsi*cphi;
_R(1, 1) = spsi*stheta*sphi + cpsi*cphi;
_R(1, 2) = ctheta*sphi;
_R(1, 3) = 0.0;
_R(2, 0) = cpsi*stheta*cphi + spsi*sphi;
_R(2, 1) = spsi*stheta*cphi - cpsi*sphi;
_R(2, 2) = ctheta*cphi;
_R(2, 3) = 0.0;
}
double _dCalcVectorDot3(const double *a, const double *b, unsigned step_a,
unsigned step_b)
{
return a[0] * b[0] + a[step_a] * b[step_b] + a[2 * step_a] * b[2 * step_b];
}
double dCalcVectorDot3(const double *a, const double *b)
{
return _dCalcVectorDot3(a, b, 1, 1);
}
double dCalcVectorDot3_41(const double *a, const double *b)
{
return _dCalcVectorDot3(a, b, 4, 1);
}
void dMultiply0_331(double *res, const double *a, const double *b)
{
double res_0, res_1, res_2;
res_0 = dCalcVectorDot3(a, b);
res_1 = dCalcVectorDot3(a + 4, b);
res_2 = dCalcVectorDot3(a + 8, b);
res[0] = res_0;
res[1] = res_1;
res[2] = res_2;
}
void dMultiply1_331(double *res, const double *a, const double *b)
{
double res_0, res_1, res_2;
res_0 = dCalcVectorDot3_41(a, b);
res_1 = dCalcVectorDot3_41(a + 1, b);
res_2 = dCalcVectorDot3_41(a + 2, b);
res[0] = res_0;
res[1] = res_1;
res[2] = res_2;
}
void dMultiply0_133(double *res, const double *a, const double *b)
{
dMultiply1_331(res, b, a);
}
void dMultiply0_333(double *res, const double *a, const double *b)
{
dMultiply0_133(res + 0, a + 0, b);
dMultiply0_133(res + 4, a + 4, b);
dMultiply0_133(res + 8, a + 8, b);
}
void dMultiply2_333(double *res, const double *a, const double *b)
{
dMultiply0_331(res + 0, b, a + 0);
dMultiply0_331(res + 4, b, a + 4);
dMultiply0_331(res + 8, b, a + 8);
}
void dMassRotate(dMass *m, const dMatrix3 R)
{
// if the body is rotated by `R' relative to its point of reference,
// the new inertia about the point of reference is:
//
// R * I * R'
//
// where I is the old inertia.
dMatrix3 t1;
double t2[3];
// dAASSERT (m);
// rotate inertia matrix
dMultiply2_333(t1, m->I, R);
dMultiply0_333(m->I, R, t1);
// ensure perfect symmetry
m->_I(1, 0) = m->_I(0, 1);
m->_I(2, 0) = m->_I(0, 2);
m->_I(2, 1) = m->_I(1, 2);
// rotate center of mass
dMultiply0_331(t2, R, m->c);
m->c[0] = t2[0];
m->c[1] = t2[1];
m->c[2] = t2[2];
}
void dSetCrossMatrixPlus(double *res, const double *a, unsigned skip)
{
const double a_0 = a[0], a_1 = a[1], a_2 = a[2];
res[1] = -a_2;
res[2] = +a_1;
res[skip+0] = +a_2;
res[skip+2] = -a_0;
res[2*skip+0] = -a_1;
res[2*skip+1] = +a_0;
}
void dMassTranslate(dMass *m, double x, double y, double z)
{
// if the body is translated by `a' relative to its point of reference,
// the new inertia about the point of reference is:
//
// I + mass*(crossmat(c)^2 - crossmat(c+a)^2)
//
// where c is the existing center of mass and I is the old inertia.
int i, j;
dMatrix3 ahat, chat, t1, t2;
double a[3];
// dAASSERT (m);
// adjust inertia matrix
dSetZero(chat, 12);
dSetCrossMatrixPlus(chat, m->c, 4);
a[0] = x + m->c[0];
a[1] = y + m->c[1];
a[2] = z + m->c[2];
dSetZero(ahat, 12);
dSetCrossMatrixPlus(ahat, a, 4);
dMultiply0_333(t1, ahat, ahat);
dMultiply0_333(t2, chat, chat);
for (i = 0; i < 3; i++)
{
for (j = 0; j < 3; j++)
{
m->_I(i, j) += m->mass * (t2[i*4+j]-t1[i*4+j]);
}
}
// ensure perfect symmetry
m->_I(1, 0) = m->_I(0, 1);
m->_I(2, 0) = m->_I(0, 2);
m->_I(2, 1) = m->_I(1, 2);
// adjust center of mass
m->c[0] += x;
m->c[1] += y;
m->c[2] += z;
}
void dMassAdd(dMass *a, const dMass *b)
{
int i;
double denom = dRecip(a->mass + b->mass);
for (i = 0; i < 3; i++)
{
a->c[i] = (a->c[i]*a->mass + b->c[i]*b->mass)*denom;
}
a->mass += b->mass;
for (i = 0; i < 12; i++)
{
a->I[i] += b->I[i];
}
}
/////////////////////////////////////////////////
/// print mass for link for debugging
void PrintMass(const std::string &_linkName, const dMass &_mass)
{
sdfdbg << "LINK NAME: [" << _linkName << "] from dMass\n";
sdfdbg << " MASS: [" << _mass.mass << "]\n";
sdfdbg << " CG: [" << _mass.c[0] << ", " << _mass.c[1] << ", "
<< _mass.c[2] << "]\n";
sdfdbg << " I: [" << _mass.I[0] << ", " << _mass.I[1] << ", "
<< _mass.I[2] << "]\n";
sdfdbg << " [" << _mass.I[4] << ", " << _mass.I[5] << ", "
<< _mass.I[6] << "]\n";
sdfdbg << " [" << _mass.I[8] << ", " << _mass.I[9] << ", "
<< _mass.I[10] << "]\n";
}
/////////////////////////////////////////////////
/// print mass for link for debugging
void PrintMass(const urdf::LinkSharedPtr _link)
{
sdfdbg << "LINK NAME: [" << _link->name << "] from dMass\n";
sdfdbg << " MASS: [" << _link->inertial->mass << "]\n";
sdfdbg << " CG: [" << _link->inertial->origin.position.x << ", "
<< _link->inertial->origin.position.y << ", "
<< _link->inertial->origin.position.z << "]\n";
sdfdbg << " I: [" << _link->inertial->ixx << ", "
<< _link->inertial->ixy << ", "
<< _link->inertial->ixz << "]\n";
sdfdbg << " [" << _link->inertial->ixy << ", "
<< _link->inertial->iyy << ", "
<< _link->inertial->iyz << "]\n";
sdfdbg << " [" << _link->inertial->ixz << ", "
<< _link->inertial->iyz << ", "
<< _link->inertial->izz << "]\n";
}
/////////////////////////////////////////////////
/// reduce fixed joints: lump inertial to parent link
void ReduceInertialToParent(urdf::LinkSharedPtr _link)
{
// now lump all contents of this _link to parent
if (_link->inertial)
{
dMatrix3 R;
double phi, theta, psi;
// get parent mass (in parent link cg frame)
dMass parentMass;
if (!_link->getParent()->inertial)
{
_link->getParent()->inertial.reset(new urdf::Inertial);
}
dMassSetParameters(&parentMass, _link->getParent()->inertial->mass,
0, 0, 0,
_link->getParent()->inertial->ixx,
_link->getParent()->inertial->iyy,
_link->getParent()->inertial->izz,
_link->getParent()->inertial->ixy,
_link->getParent()->inertial->ixz,
_link->getParent()->inertial->iyz);
// transform parent inertia to parent link origin
_link->getParent()->inertial->origin.rotation.getRPY(phi, theta, psi);
dRFromEulerAngles(R, -phi, 0, 0);
dMassRotate(&parentMass, R);
dRFromEulerAngles(R, 0, -theta, 0);
dMassRotate(&parentMass, R);
dRFromEulerAngles(R, 0, 0, -psi);
dMassRotate(&parentMass, R);
// un-translate link mass from cg(inertial frame) into link frame
dMassTranslate(&parentMass,
_link->getParent()->inertial->origin.position.x,
_link->getParent()->inertial->origin.position.y,
_link->getParent()->inertial->origin.position.z);
PrintMass("parent: " + _link->getParent()->name, parentMass);
// PrintMass(_link->getParent());
//////////////////////////////////////////////
// //
// create a_link mass (in _link's cg frame) //
// //
//////////////////////////////////////////////
dMass linkMass;
dMassSetParameters(&linkMass, _link->inertial->mass,
0, 0, 0,
_link->inertial->ixx,
_link->inertial->iyy,
_link->inertial->izz,
_link->inertial->ixy,
_link->inertial->ixz,
_link->inertial->iyz);
PrintMass("link : " + _link->name, linkMass);
////////////////////////////////////////////
// //
// from cg (inertial frame) to link frame //
// //
////////////////////////////////////////////
// Un-rotate _link mass from cg(inertial frame) into link frame
_link->inertial->origin.rotation.getRPY(phi, theta, psi);
dRFromEulerAngles(R, -phi, 0, 0);
dMassRotate(&linkMass, R);
dRFromEulerAngles(R, 0, -theta, 0);
dMassRotate(&linkMass, R);
dRFromEulerAngles(R, 0, 0, -psi);
dMassRotate(&linkMass, R);
// un-translate link mass from cg(inertial frame) into link frame
dMassTranslate(&linkMass,
_link->inertial->origin.position.x,
_link->inertial->origin.position.y,
_link->inertial->origin.position.z);
////////////////////////////////////////////
// //
// from link frame to parent link frame //
// //
////////////////////////////////////////////
// un-rotate _link mass into parent link frame
_link->parent_joint->parent_to_joint_origin_transform.rotation.getRPY(
phi, theta, psi);
dRFromEulerAngles(R, -phi, 0, 0);
dMassRotate(&linkMass, R);
dRFromEulerAngles(R, 0, -theta, 0);
dMassRotate(&linkMass, R);
dRFromEulerAngles(R, 0, 0, -psi);
dMassRotate(&linkMass, R);
// un-translate _link mass into parent link frame
dMassTranslate(&linkMass,
_link->parent_joint->parent_to_joint_origin_transform.position.x,
_link->parent_joint->parent_to_joint_origin_transform.position.y,
_link->parent_joint->parent_to_joint_origin_transform.position.z);
PrintMass("link in parent link: " + _link->name, linkMass);
//
// now linkMass is in the parent frame, add linkMass to parentMass
// new parentMass should be combined inertia,
// centered at parent link inertial frame.
//
dMassAdd(&parentMass, &linkMass);
PrintMass("combined: " + _link->getParent()->name, parentMass);
//
// Set new combined inertia in parent link frame into parent link urdf
//
// save combined mass
_link->getParent()->inertial->mass = parentMass.mass;
// save CoG location
_link->getParent()->inertial->origin.position.x = parentMass.c[0];
_link->getParent()->inertial->origin.position.y = parentMass.c[1];
_link->getParent()->inertial->origin.position.z = parentMass.c[2];
// get MOI at new CoG location
dMassTranslate(&parentMass,
-_link->getParent()->inertial->origin.position.x,
-_link->getParent()->inertial->origin.position.y,
-_link->getParent()->inertial->origin.position.z);
// rotate MOI at new CoG location
_link->getParent()->inertial->origin.rotation.getRPY(phi, theta, psi);
dRFromEulerAngles(R, phi, theta, psi);
dMassRotate(&parentMass, R);
// save new combined MOI
_link->getParent()->inertial->ixx = parentMass.I[0+4*0];
_link->getParent()->inertial->iyy = parentMass.I[1+4*1];
_link->getParent()->inertial->izz = parentMass.I[2+4*2];
_link->getParent()->inertial->ixy = parentMass.I[0+4*1];
_link->getParent()->inertial->ixz = parentMass.I[0+4*2];
_link->getParent()->inertial->iyz = parentMass.I[1+4*2];
// final urdf inertia check
PrintMass(_link->getParent());
}
}
/////////////////////////////////////////////////
/// \brief reduce fixed joints: lump visuals to parent link
/// \param[in] _link take all visuals from _link and lump/move them
/// to the parent link (_link->getParentLink()).
void ReduceVisualsToParent(urdf::LinkSharedPtr _link)
{
// lump all visuals of _link to _link->getParent().
// modify visual name (urdf 0.3.x) or
// visual group name (urdf 0.2.x)
// to indicate that it was lumped (fixed joint reduced)
// from another descendant link connected by a fixed joint.
//
// Algorithm for generating new name (or group name) is:
// original name + kLumpPrefix+original link name (urdf 0.3.x)
// original group name + kLumpPrefix+original link name (urdf 0.2.x)
// The purpose is to track where this visual came from
// (original parent link name before lumping/reducing).
for (std::vector<urdf::VisualSharedPtr>::iterator
visualIt = _link->visual_array.begin();
visualIt != _link->visual_array.end(); ++visualIt)
{
// 20151116: changelog for pull request #235
std::string newVisualName;
std::size_t lumpIndex = (*visualIt)->name.find(kLumpPrefix);
if (lumpIndex != std::string::npos)
{
newVisualName = (*visualIt)->name;
sdfdbg << "re-lumping visual [" << (*visualIt)->name
<< "] for link [" << _link->name
<< "] to parent [" << _link->getParent()->name
<< "] with name [" << newVisualName << "]\n";
}
else
{
if ((*visualIt)->name.empty())
{
newVisualName = _link->name;
}
else
{
newVisualName = (*visualIt)->name;
}
sdfdbg << "lumping visual [" << (*visualIt)->name
<< "] for link [" << _link->name
<< "] to parent [" << _link->getParent()->name
<< "] with name [" << newVisualName << "]\n";
}
// transform visual origin from _link frame to
// parent link frame before adding to parent
(*visualIt)->origin = TransformToParentFrame(
(*visualIt)->origin,
_link->parent_joint->parent_to_joint_origin_transform);
// add the modified visual to parent
ReduceVisualToParent(_link->getParent(), newVisualName,
*visualIt);