1 |
commit: 69246bcb80a191e968a6ceed579a78f7f70a2aed |
2 |
Author: Alexis Ballier <aballier <AT> gentoo <DOT> org> |
3 |
AuthorDate: Sun Jul 24 14:01:26 2016 +0000 |
4 |
Commit: Alexis Ballier <aballier <AT> gentoo <DOT> org> |
5 |
CommitDate: Tue Jul 26 09:18:30 2016 +0000 |
6 |
URL: https://gitweb.gentoo.org/repo/gentoo.git/commit/?id=69246bcb |
7 |
|
8 |
dev-libs/sdformat: fix build with urdfdom-1 and add := dep on it |
9 |
|
10 |
Package-Manager: portage-2.3.0 |
11 |
|
12 |
dev-libs/sdformat/files/urdfdom1.patch | 392 +++++++++++++++++++++ |
13 |
...ormat-4.1.1.ebuild => sdformat-4.1.1-r1.ebuild} | 3 +- |
14 |
2 files changed, 394 insertions(+), 1 deletion(-) |
15 |
|
16 |
diff --git a/dev-libs/sdformat/files/urdfdom1.patch b/dev-libs/sdformat/files/urdfdom1.patch |
17 |
new file mode 100644 |
18 |
index 0000000..d76376a |
19 |
--- /dev/null |
20 |
+++ b/dev-libs/sdformat/files/urdfdom1.patch |
21 |
@@ -0,0 +1,392 @@ |
22 |
+Index: sdformat-4.1.1/src/parser_urdf.cc |
23 |
+=================================================================== |
24 |
+--- sdformat-4.1.1.orig/src/parser_urdf.cc |
25 |
++++ sdformat-4.1.1/src/parser_urdf.cc |
26 |
+@@ -25,6 +25,7 @@ |
27 |
+ #include "urdf_model/model.h" |
28 |
+ #include "urdf_model/link.h" |
29 |
+ #include "urdf_parser/urdf_parser.h" |
30 |
++#include <urdf_model/utils.h> |
31 |
+ |
32 |
+ #include "sdf/SDFExtension.hh" |
33 |
+ #include "sdf/parser_urdf.hh" |
34 |
+@@ -32,10 +33,10 @@ |
35 |
+ |
36 |
+ using namespace sdf; |
37 |
+ |
38 |
+-typedef boost::shared_ptr<urdf::Collision> UrdfCollisionPtr; |
39 |
+-typedef boost::shared_ptr<urdf::Visual> UrdfVisualPtr; |
40 |
+-typedef boost::shared_ptr<urdf::Link> UrdfLinkPtr; |
41 |
+-typedef boost::shared_ptr<const urdf::Link> ConstUrdfLinkPtr; |
42 |
++typedef std::shared_ptr<urdf::Collision> UrdfCollisionPtr; |
43 |
++typedef std::shared_ptr<urdf::Visual> UrdfVisualPtr; |
44 |
++typedef std::shared_ptr<urdf::Link> UrdfLinkPtr; |
45 |
++typedef std::shared_ptr<const urdf::Link> ConstUrdfLinkPtr; |
46 |
+ typedef std::shared_ptr<TiXmlElement> TiXmlElementPtr; |
47 |
+ typedef std::shared_ptr<SDFExtension> SDFExtensionPtr; |
48 |
+ typedef std::map<std::string, std::vector<SDFExtensionPtr> > |
49 |
+@@ -78,7 +79,7 @@ void InsertSDFExtensionJoint(TiXmlElemen |
50 |
+ /// reduced fixed joints: check if a fixed joint should be lumped |
51 |
+ /// checking both the joint type and if disabledFixedJointLumping |
52 |
+ /// option is set |
53 |
+-bool FixedJointShouldBeReduced(boost::shared_ptr<urdf::Joint> _jnt); |
54 |
++bool FixedJointShouldBeReduced(std::shared_ptr<urdf::Joint> _jnt); |
55 |
+ |
56 |
+ /// reduced fixed joints: apply transform reduction for ray sensors |
57 |
+ /// in extensions when doing fixed joint reduction |
58 |
+@@ -217,9 +218,9 @@ std::string Values2str(unsigned int _cou |
59 |
+ |
60 |
+ |
61 |
+ void CreateGeometry(TiXmlElement* _elem, |
62 |
+- boost::shared_ptr<urdf::Geometry> _geometry); |
63 |
++ std::shared_ptr<urdf::Geometry> _geometry); |
64 |
+ |
65 |
+-std::string GetGeometryBoundingBox(boost::shared_ptr<urdf::Geometry> _geometry, |
66 |
++std::string GetGeometryBoundingBox(std::shared_ptr<urdf::Geometry> _geometry, |
67 |
+ double *_sizeVals); |
68 |
+ |
69 |
+ ignition::math::Pose3d inverseTransformToParentFrame( |
70 |
+@@ -254,7 +255,7 @@ urdf::Vector3 ParseVector3(const std::st |
71 |
+ std::vector<std::string> pieces; |
72 |
+ std::vector<double> vals; |
73 |
+ |
74 |
+- boost::split(pieces, _str, boost::is_any_of(" ")); |
75 |
++ urdf::split_string(pieces, _str, " "); |
76 |
+ for (unsigned int i = 0; i < pieces.size(); ++i) |
77 |
+ { |
78 |
+ if (pieces[i] != "") |
79 |
+@@ -262,7 +263,7 @@ urdf::Vector3 ParseVector3(const std::st |
80 |
+ try |
81 |
+ { |
82 |
+ vals.push_back(_scale |
83 |
+- * boost::lexical_cast<double>(pieces[i].c_str())); |
84 |
++ * std::stod(pieces[i].c_str())); |
85 |
+ } |
86 |
+ catch(boost::bad_lexical_cast &) |
87 |
+ { |
88 |
+@@ -349,7 +350,7 @@ void ReduceCollisionToParent(UrdfLinkPtr |
89 |
+ UrdfCollisionPtr _collision) |
90 |
+ { |
91 |
+ #ifndef URDF_GE_0P3 |
92 |
+- boost::shared_ptr<std::vector<UrdfCollisionPtr> > cols; |
93 |
++ std::shared_ptr<std::vector<UrdfCollisionPtr> > cols; |
94 |
+ cols = _parentLink->getCollisions(_name); |
95 |
+ |
96 |
+ if (!cols) |
97 |
+@@ -427,7 +428,7 @@ void ReduceVisualToParent(UrdfLinkPtr _p |
98 |
+ UrdfVisualPtr _visual) |
99 |
+ { |
100 |
+ #ifndef URDF_GE_0P3 |
101 |
+- boost::shared_ptr<std::vector<UrdfVisualPtr> > viss; |
102 |
++ std::shared_ptr<std::vector<UrdfVisualPtr> > viss; |
103 |
+ viss = _parentLink->getVisuals(_name); |
104 |
+ |
105 |
+ if (!viss) |
106 |
+@@ -950,7 +951,7 @@ void ReduceVisualsToParent(UrdfLinkPtr _ |
107 |
+ // (original parent link name before lumping/reducing). |
108 |
+ #ifndef URDF_GE_0P3 |
109 |
+ for (std::map<std::string, |
110 |
+- boost::shared_ptr<std::vector<UrdfVisualPtr> > >::iterator |
111 |
++ std::shared_ptr<std::vector<UrdfVisualPtr> > >::iterator |
112 |
+ visualsIt = _link->visual_groups.begin(); |
113 |
+ visualsIt != _link->visual_groups.end(); ++visualsIt) |
114 |
+ { |
115 |
+@@ -1057,7 +1058,7 @@ void ReduceCollisionsToParent(UrdfLinkPt |
116 |
+ // (original parent link name before lumping/reducing). |
117 |
+ #ifndef URDF_GE_0P3 |
118 |
+ for (std::map<std::string, |
119 |
+- boost::shared_ptr<std::vector<UrdfCollisionPtr> > >::iterator |
120 |
++ std::shared_ptr<std::vector<UrdfCollisionPtr> > >::iterator |
121 |
+ collisionsIt = _link->collision_groups.begin(); |
122 |
+ collisionsIt != _link->collision_groups.end(); ++collisionsIt) |
123 |
+ { |
124 |
+@@ -1160,7 +1161,7 @@ void ReduceJointsToParent(UrdfLinkPtr _l |
125 |
+ // a parent link up stream that does not have a fixed parentJoint |
126 |
+ for (unsigned int i = 0 ; i < _link->child_links.size() ; ++i) |
127 |
+ { |
128 |
+- boost::shared_ptr<urdf::Joint> parentJoint = |
129 |
++ std::shared_ptr<urdf::Joint> parentJoint = |
130 |
+ _link->child_links[i]->parent_joint; |
131 |
+ if (!FixedJointShouldBeReduced(parentJoint)) |
132 |
+ { |
133 |
+@@ -1431,31 +1432,31 @@ void URDF2SDF::ParseSDFExtension(TiXmlDo |
134 |
+ else if (childElem->ValueStr() == "dampingFactor") |
135 |
+ { |
136 |
+ sdf->isDampingFactor = true; |
137 |
+- sdf->dampingFactor = boost::lexical_cast<double>( |
138 |
++ sdf->dampingFactor = std::stod( |
139 |
+ GetKeyValueAsString(childElem).c_str()); |
140 |
+ } |
141 |
+ else if (childElem->ValueStr() == "maxVel") |
142 |
+ { |
143 |
+ sdf->isMaxVel = true; |
144 |
+- sdf->maxVel = boost::lexical_cast<double>( |
145 |
++ sdf->maxVel = std::stod( |
146 |
+ GetKeyValueAsString(childElem).c_str()); |
147 |
+ } |
148 |
+ else if (childElem->ValueStr() == "minDepth") |
149 |
+ { |
150 |
+ sdf->isMinDepth = true; |
151 |
+- sdf->minDepth = boost::lexical_cast<double>( |
152 |
++ sdf->minDepth = std::stod( |
153 |
+ GetKeyValueAsString(childElem).c_str()); |
154 |
+ } |
155 |
+ else if (childElem->ValueStr() == "mu1") |
156 |
+ { |
157 |
+ sdf->isMu1 = true; |
158 |
+- sdf->mu1 = boost::lexical_cast<double>( |
159 |
++ sdf->mu1 = std::stod( |
160 |
+ GetKeyValueAsString(childElem).c_str()); |
161 |
+ } |
162 |
+ else if (childElem->ValueStr() == "mu2") |
163 |
+ { |
164 |
+ sdf->isMu2 = true; |
165 |
+- sdf->mu2 = boost::lexical_cast<double>( |
166 |
++ sdf->mu2 = std::stod( |
167 |
+ GetKeyValueAsString(childElem).c_str()); |
168 |
+ } |
169 |
+ else if (childElem->ValueStr() == "fdir1") |
170 |
+@@ -1465,13 +1466,13 @@ void URDF2SDF::ParseSDFExtension(TiXmlDo |
171 |
+ else if (childElem->ValueStr() == "kp") |
172 |
+ { |
173 |
+ sdf->isKp = true; |
174 |
+- sdf->kp = boost::lexical_cast<double>( |
175 |
++ sdf->kp = std::stod( |
176 |
+ GetKeyValueAsString(childElem).c_str()); |
177 |
+ } |
178 |
+ else if (childElem->ValueStr() == "kd") |
179 |
+ { |
180 |
+ sdf->isKd = true; |
181 |
+- sdf->kd = boost::lexical_cast<double>( |
182 |
++ sdf->kd = std::stod( |
183 |
+ GetKeyValueAsString(childElem).c_str()); |
184 |
+ } |
185 |
+ else if (childElem->ValueStr() == "selfCollide") |
186 |
+@@ -1488,13 +1489,13 @@ void URDF2SDF::ParseSDFExtension(TiXmlDo |
187 |
+ else if (childElem->ValueStr() == "maxContacts") |
188 |
+ { |
189 |
+ sdf->isMaxContacts = true; |
190 |
+- sdf->maxContacts = boost::lexical_cast<int>( |
191 |
++ sdf->maxContacts = std::stoi( |
192 |
+ GetKeyValueAsString(childElem).c_str()); |
193 |
+ } |
194 |
+ else if (childElem->ValueStr() == "laserRetro") |
195 |
+ { |
196 |
+ sdf->isLaserRetro = true; |
197 |
+- sdf->laserRetro = boost::lexical_cast<double>( |
198 |
++ sdf->laserRetro = std::stod( |
199 |
+ GetKeyValueAsString(childElem).c_str()); |
200 |
+ } |
201 |
+ else if (childElem->ValueStr() == "springReference") |
202 |
+@@ -1510,37 +1511,37 @@ void URDF2SDF::ParseSDFExtension(TiXmlDo |
203 |
+ else if (childElem->ValueStr() == "stopCfm") |
204 |
+ { |
205 |
+ sdf->isStopCfm = true; |
206 |
+- sdf->stopCfm = boost::lexical_cast<double>( |
207 |
++ sdf->stopCfm = std::stod( |
208 |
+ GetKeyValueAsString(childElem).c_str()); |
209 |
+ } |
210 |
+ else if (childElem->ValueStr() == "stopErp") |
211 |
+ { |
212 |
+ sdf->isStopErp = true; |
213 |
+- sdf->stopErp = boost::lexical_cast<double>( |
214 |
++ sdf->stopErp = std::stod( |
215 |
+ GetKeyValueAsString(childElem).c_str()); |
216 |
+ } |
217 |
+ else if (childElem->ValueStr() == "stopKp") |
218 |
+ { |
219 |
+ sdf->isStopKp = true; |
220 |
+- sdf->stopKp = boost::lexical_cast<double>( |
221 |
++ sdf->stopKp = std::stod( |
222 |
+ GetKeyValueAsString(childElem).c_str()); |
223 |
+ } |
224 |
+ else if (childElem->ValueStr() == "stopKd") |
225 |
+ { |
226 |
+ sdf->isStopKd = true; |
227 |
+- sdf->stopKd = boost::lexical_cast<double>( |
228 |
++ sdf->stopKd = std::stod( |
229 |
+ GetKeyValueAsString(childElem).c_str()); |
230 |
+ } |
231 |
+ else if (childElem->ValueStr() == "initialJointPosition") |
232 |
+ { |
233 |
+ sdf->isInitialJointPosition = true; |
234 |
+- sdf->initialJointPosition = boost::lexical_cast<double>( |
235 |
++ sdf->initialJointPosition = std::stod( |
236 |
+ GetKeyValueAsString(childElem).c_str()); |
237 |
+ } |
238 |
+ else if (childElem->ValueStr() == "fudgeFactor") |
239 |
+ { |
240 |
+ sdf->isFudgeFactor = true; |
241 |
+- sdf->fudgeFactor = boost::lexical_cast<double>( |
242 |
++ sdf->fudgeFactor = std::stod( |
243 |
+ GetKeyValueAsString(childElem).c_str()); |
244 |
+ } |
245 |
+ else if (childElem->ValueStr() == "provideFeedback") |
246 |
+@@ -1917,7 +1918,7 @@ void InsertSDFExtensionCollision(TiXmlEl |
247 |
+ if ((*ge)->isMaxContacts) |
248 |
+ { |
249 |
+ AddKeyValue(_elem, "max_contacts", |
250 |
+- boost::lexical_cast<std::string>((*ge)->maxContacts)); |
251 |
++ std::to_string((*ge)->maxContacts)); |
252 |
+ } |
253 |
+ } |
254 |
+ } |
255 |
+@@ -2339,7 +2340,7 @@ void InsertSDFExtensionRobot(TiXmlElemen |
256 |
+ |
257 |
+ //////////////////////////////////////////////////////////////////////////////// |
258 |
+ void CreateGeometry(TiXmlElement* _elem, |
259 |
+- boost::shared_ptr<urdf::Geometry> _geom) |
260 |
++ std::shared_ptr<urdf::Geometry> _geom) |
261 |
+ { |
262 |
+ TiXmlElement *sdfGeometry = new TiXmlElement("geometry"); |
263 |
+ |
264 |
+@@ -2351,8 +2352,8 @@ void CreateGeometry(TiXmlElement* _elem, |
265 |
+ case urdf::Geometry::BOX: |
266 |
+ type = "box"; |
267 |
+ { |
268 |
+- boost::shared_ptr<const urdf::Box> box; |
269 |
+- box = boost::dynamic_pointer_cast< const urdf::Box >(_geom); |
270 |
++ std::shared_ptr<const urdf::Box> box; |
271 |
++ box = std::dynamic_pointer_cast< const urdf::Box >(_geom); |
272 |
+ int sizeCount = 3; |
273 |
+ double sizeVals[3]; |
274 |
+ sizeVals[0] = box->dim.x; |
275 |
+@@ -2366,8 +2367,8 @@ void CreateGeometry(TiXmlElement* _elem, |
276 |
+ case urdf::Geometry::CYLINDER: |
277 |
+ type = "cylinder"; |
278 |
+ { |
279 |
+- boost::shared_ptr<const urdf::Cylinder> cylinder; |
280 |
+- cylinder = boost::dynamic_pointer_cast<const urdf::Cylinder >(_geom); |
281 |
++ std::shared_ptr<const urdf::Cylinder> cylinder; |
282 |
++ cylinder = std::dynamic_pointer_cast<const urdf::Cylinder >(_geom); |
283 |
+ geometryType = new TiXmlElement(type); |
284 |
+ AddKeyValue(geometryType, "length", |
285 |
+ Values2str(1, &cylinder->length)); |
286 |
+@@ -2378,8 +2379,8 @@ void CreateGeometry(TiXmlElement* _elem, |
287 |
+ case urdf::Geometry::SPHERE: |
288 |
+ type = "sphere"; |
289 |
+ { |
290 |
+- boost::shared_ptr<const urdf::Sphere> sphere; |
291 |
+- sphere = boost::dynamic_pointer_cast<const urdf::Sphere >(_geom); |
292 |
++ std::shared_ptr<const urdf::Sphere> sphere; |
293 |
++ sphere = std::dynamic_pointer_cast<const urdf::Sphere >(_geom); |
294 |
+ geometryType = new TiXmlElement(type); |
295 |
+ AddKeyValue(geometryType, "radius", |
296 |
+ Values2str(1, &sphere->radius)); |
297 |
+@@ -2388,8 +2389,8 @@ void CreateGeometry(TiXmlElement* _elem, |
298 |
+ case urdf::Geometry::MESH: |
299 |
+ type = "mesh"; |
300 |
+ { |
301 |
+- boost::shared_ptr<const urdf::Mesh> mesh; |
302 |
+- mesh = boost::dynamic_pointer_cast<const urdf::Mesh >(_geom); |
303 |
++ std::shared_ptr<const urdf::Mesh> mesh; |
304 |
++ mesh = std::dynamic_pointer_cast<const urdf::Mesh >(_geom); |
305 |
+ geometryType = new TiXmlElement(type); |
306 |
+ AddKeyValue(geometryType, "scale", Vector32Str(mesh->scale)); |
307 |
+ // do something more to meshes |
308 |
+@@ -2451,7 +2452,7 @@ void CreateGeometry(TiXmlElement* _elem, |
309 |
+ |
310 |
+ //////////////////////////////////////////////////////////////////////////////// |
311 |
+ std::string GetGeometryBoundingBox( |
312 |
+- boost::shared_ptr<urdf::Geometry> _geom, double *_sizeVals) |
313 |
++ std::shared_ptr<urdf::Geometry> _geom, double *_sizeVals) |
314 |
+ { |
315 |
+ std::string type; |
316 |
+ |
317 |
+@@ -2460,8 +2461,8 @@ std::string GetGeometryBoundingBox( |
318 |
+ case urdf::Geometry::BOX: |
319 |
+ type = "box"; |
320 |
+ { |
321 |
+- boost::shared_ptr<const urdf::Box> box; |
322 |
+- box = boost::dynamic_pointer_cast<const urdf::Box >(_geom); |
323 |
++ std::shared_ptr<const urdf::Box> box; |
324 |
++ box = std::dynamic_pointer_cast<const urdf::Box >(_geom); |
325 |
+ _sizeVals[0] = box->dim.x; |
326 |
+ _sizeVals[1] = box->dim.y; |
327 |
+ _sizeVals[2] = box->dim.z; |
328 |
+@@ -2470,8 +2471,8 @@ std::string GetGeometryBoundingBox( |
329 |
+ case urdf::Geometry::CYLINDER: |
330 |
+ type = "cylinder"; |
331 |
+ { |
332 |
+- boost::shared_ptr<const urdf::Cylinder> cylinder; |
333 |
+- cylinder = boost::dynamic_pointer_cast<const urdf::Cylinder >(_geom); |
334 |
++ std::shared_ptr<const urdf::Cylinder> cylinder; |
335 |
++ cylinder = std::dynamic_pointer_cast<const urdf::Cylinder >(_geom); |
336 |
+ _sizeVals[0] = cylinder->radius * 2; |
337 |
+ _sizeVals[1] = cylinder->radius * 2; |
338 |
+ _sizeVals[2] = cylinder->length; |
339 |
+@@ -2480,16 +2481,16 @@ std::string GetGeometryBoundingBox( |
340 |
+ case urdf::Geometry::SPHERE: |
341 |
+ type = "sphere"; |
342 |
+ { |
343 |
+- boost::shared_ptr<const urdf::Sphere> sphere; |
344 |
+- sphere = boost::dynamic_pointer_cast<const urdf::Sphere >(_geom); |
345 |
++ std::shared_ptr<const urdf::Sphere> sphere; |
346 |
++ sphere = std::dynamic_pointer_cast<const urdf::Sphere >(_geom); |
347 |
+ _sizeVals[0] = _sizeVals[1] = _sizeVals[2] = sphere->radius * 2; |
348 |
+ } |
349 |
+ break; |
350 |
+ case urdf::Geometry::MESH: |
351 |
+ type = "trimesh"; |
352 |
+ { |
353 |
+- boost::shared_ptr<const urdf::Mesh> mesh; |
354 |
+- mesh = boost::dynamic_pointer_cast<const urdf::Mesh >(_geom); |
355 |
++ std::shared_ptr<const urdf::Mesh> mesh; |
356 |
++ mesh = std::dynamic_pointer_cast<const urdf::Mesh >(_geom); |
357 |
+ _sizeVals[0] = mesh->scale.x; |
358 |
+ _sizeVals[1] = mesh->scale.y; |
359 |
+ _sizeVals[2] = mesh->scale.z; |
360 |
+@@ -2513,7 +2514,7 @@ void PrintCollisionGroups(UrdfLinkPtr _l |
361 |
+ << static_cast<int>(_link->collision_groups.size()) |
362 |
+ << "] collisions.\n"; |
363 |
+ for (std::map<std::string, |
364 |
+- boost::shared_ptr<std::vector<UrdfCollisionPtr > > >::iterator |
365 |
++ std::shared_ptr<std::vector<UrdfCollisionPtr > > >::iterator |
366 |
+ colsIt = _link->collision_groups.begin(); |
367 |
+ colsIt != _link->collision_groups.end(); ++colsIt) |
368 |
+ { |
369 |
+@@ -2906,7 +2907,7 @@ void CreateCollisions(TiXmlElement* _ele |
370 |
+ // lumped meshes (fixed joint reduction) |
371 |
+ #ifndef URDF_GE_0P3 |
372 |
+ for (std::map<std::string, |
373 |
+- boost::shared_ptr<std::vector<UrdfCollisionPtr> > >::const_iterator |
374 |
++ std::shared_ptr<std::vector<UrdfCollisionPtr> > >::const_iterator |
375 |
+ collisionsIt = _link->collision_groups.begin(); |
376 |
+ collisionsIt != _link->collision_groups.end(); ++collisionsIt) |
377 |
+ { |
378 |
+@@ -3028,7 +3029,7 @@ void CreateVisuals(TiXmlElement* _elem, |
379 |
+ // lumped meshes (fixed joint reduction) |
380 |
+ #ifndef URDF_GE_0P3 |
381 |
+ for (std::map<std::string, |
382 |
+- boost::shared_ptr<std::vector<UrdfVisualPtr> > >::const_iterator |
383 |
++ std::shared_ptr<std::vector<UrdfVisualPtr> > >::const_iterator |
384 |
+ visualsIt = _link->visual_groups.begin(); |
385 |
+ visualsIt != _link->visual_groups.end(); ++visualsIt) |
386 |
+ { |
387 |
+@@ -3411,7 +3412,7 @@ TiXmlDocument URDF2SDF::InitModelString( |
388 |
+ g_enforceLimits = _enforceLimits; |
389 |
+ |
390 |
+ // Create a RobotModel from string |
391 |
+- boost::shared_ptr<urdf::ModelInterface> robotModel = |
392 |
++ std::shared_ptr<urdf::ModelInterface> robotModel = |
393 |
+ urdf::parseURDF(_urdfStr.c_str()); |
394 |
+ |
395 |
+ // an xml object to hold the xml result |
396 |
+@@ -3453,7 +3454,7 @@ TiXmlDocument URDF2SDF::InitModelString( |
397 |
+ // fixed joint lumping only for selected joints |
398 |
+ if (g_reduceFixedJoints) |
399 |
+ ReduceFixedJoints(robot, |
400 |
+- (boost::const_pointer_cast< urdf::Link >(rootLink))); |
401 |
++ (std::const_pointer_cast< urdf::Link >(rootLink))); |
402 |
+ |
403 |
+ if (rootLink->name == "world") |
404 |
+ { |
405 |
+@@ -3514,7 +3515,7 @@ TiXmlDocument URDF2SDF::InitModelFile(co |
406 |
+ } |
407 |
+ |
408 |
+ //////////////////////////////////////////////////////////////////////////////// |
409 |
+-bool FixedJointShouldBeReduced(boost::shared_ptr<urdf::Joint> _jnt) |
410 |
++bool FixedJointShouldBeReduced(std::shared_ptr<urdf::Joint> _jnt) |
411 |
+ { |
412 |
+ // A joint should be lumped only if its type is fixed and |
413 |
+ // the disabledFixedJointLumping joint option is not set |
414 |
|
415 |
diff --git a/dev-libs/sdformat/sdformat-4.1.1.ebuild b/dev-libs/sdformat/sdformat-4.1.1-r1.ebuild |
416 |
similarity index 93% |
417 |
rename from dev-libs/sdformat/sdformat-4.1.1.ebuild |
418 |
rename to dev-libs/sdformat/sdformat-4.1.1-r1.ebuild |
419 |
index 68deded..66bc9be 100644 |
420 |
--- a/dev-libs/sdformat/sdformat-4.1.1.ebuild |
421 |
+++ b/dev-libs/sdformat/sdformat-4.1.1-r1.ebuild |
422 |
@@ -17,7 +17,7 @@ KEYWORDS="~amd64" |
423 |
IUSE="" |
424 |
|
425 |
RDEPEND=" |
426 |
- dev-libs/urdfdom |
427 |
+ >=dev-libs/urdfdom-1:= |
428 |
dev-libs/tinyxml |
429 |
dev-libs/boost:= |
430 |
sci-libs/ignition-math:2= |
431 |
@@ -27,6 +27,7 @@ DEPEND="${RDEPEND} |
432 |
virtual/pkgconfig |
433 |
" |
434 |
CMAKE_BUILD_TYPE=RelWithDebInfo |
435 |
+PATCHES=( "${FILESDIR}/urdfdom1.patch" ) |
436 |
|
437 |
src_configure() { |
438 |
echo "set (CMAKE_C_FLAGS_ALL \"${CXXFLAGS} \${CMAKE_C_FLAGS_ALL}\")" > "${S}/cmake/HostCFlags.cmake" |