6 #ifdef PINOCCHIO_WITH_HPP_FCL
11 #endif // PINOCCHIO_WITH_HPP_FCL
21 double pi = boost::math::constants::pi<double>();
22 if (geomType ==
"box")
26 else if (geomType ==
"cylinder")
28 return 2 * pi * std::pow(
size(0), 2) *
size(1);
30 else if (geomType ==
"sphere")
32 return 4.0 / 3 * pi * std::pow(
size(0), 3);
34 else if (geomType ==
"capsule")
36 return 4.0 / 3 * pi * std::pow(
size(0), 3) + 2 * pi * std::pow(
size(0), 2) *
size(1);
38 else if (geomType ==
"ellipsoid")
40 return 4.0 / 3 * pi *
size.prod();
44 throw std::invalid_argument(
"geometry type does not exist");
67 #ifdef PINOCCHIO_WITH_HPP_FCL
70 const MjcfGeom & geom,
71 const MjcfGraph & currentGraph,
72 std::string & meshPath,
73 Eigen::Vector3d & meshScale)
75 if (geom.geomType ==
"mesh")
77 MjcfMesh currentMesh = currentGraph.mapOfMeshes.at(geom.meshName);
78 meshPath = currentMesh.filePath;
79 meshScale = currentMesh.scale;
83 else if (geom.geomType ==
"cylinder")
85 meshPath =
"CYLINDER";
87 double radius = geom.size(0);
88 double height = geom.size(1) * 2;
91 else if (geom.geomType ==
"box")
95 double x = geom.size(0);
96 double y = geom.size(1);
97 double z = geom.size(2);
98 return std::make_shared<fcl::Box>(x, y, z);
100 else if (geom.geomType ==
"sphere")
103 meshScale << 1, 1, 1;
104 double radius = geom.size(0);
105 return std::make_shared<fcl::Sphere>(
radius);
107 else if (geom.geomType ==
"ellipsoid")
109 meshPath =
"ELLIPSOID";
110 meshScale << 1, 1, 1;
111 double rx = geom.size(0);
112 double ry = geom.size(1);
113 double rz = geom.size(2);
114 return std::make_shared<fcl::Ellipsoid>(rx, ry, rz);
116 else if (geom.geomType ==
"capsule")
118 meshPath =
"CAPSULE";
119 meshScale << 1, 1, 1;
120 double radius = geom.size(0);
121 double height = geom.size(1) * 2;
125 throw std::invalid_argument(
"Unknown geometry type :");
135 return std::make_shared<fcl::CollisionGeometry>();
151 const std::string & bodyName = currentBody.
bodyName;
155 const SE3 & bodyPlacement =
frame.placement;
157 std::size_t objectId = 0;
160 std::string meshPath =
"";
161 Eigen::Vector3d meshScale(Eigen::Vector3d::Ones());
169 std::string texturePath;
170 if (!geom.materialName.empty())
175 if (!
mat.texture.empty())
181 const SE3 geomPlacement = bodyPlacement * geom.geomPlacement;
182 std::ostringstream geometry_object_suffix;
183 geometry_object_suffix <<
"_" << objectId;
184 std::string geometry_object_name = std::string(bodyName + geometry_object_suffix.str());
198 auto text_s = el.get_optional<std::string>(
"<xmlattr>.texture");
203 auto single_v = el.get_optional<
float>(
"<xmlattr>.emission");
208 if ((single_v = el.get_optional<
float>(
"<xmlattr>.specular")))
212 if ((single_v = el.get_optional<
float>(
"<xmlattr>.shininess")))
215 if ((single_v = el.get_optional<
float>(
"<xmlattr>.reflectance")))
218 auto rgba_ = el.get_optional<std::string>(
"<xmlattr>.rgba");
220 rgba = internal::getVectorFromStream<4>(*rgba_);
225 if (el.get_child_optional(
"<xmlattr>.pos") && el.get_child_optional(
"<xmlattr>.fromto"))
226 throw std::invalid_argument(
"Both pos and fromto are defined in geom object");
232 auto value_v = el.get_optional<
double>(
"<xmlattr>.density");
237 auto val_v = el.get_optional<
int>(
"<xmlattr>.contype");
241 if ((val_v = el.get_optional<
int>(
"<xmlattr>.conaffinity")))
244 if ((val_v = el.get_optional<
int>(
"<xmlattr>.group")))
248 massGeom = el.get_optional<
double>(
"<xmlattr>.mass");
251 auto value_s = el.get_optional<std::string>(
"<xmlattr>.shellinertia");
253 throw std::invalid_argument(
"Shell inertia computation is not supported yet.");
256 if ((value_s = el.get_optional<std::string>(
"<xmlattr>.type")))
260 if ((value_s = el.get_optional<std::string>(
"<xmlattr>.material")))
265 value_s = el.get_optional<std::string>(
"<xmlattr>.mesh");
271 if ((value_s = el.get_optional<std::string>(
"<xmlattr>.rgba")))
272 rgba = internal::getVectorFromStream<4>(*value_s);
275 if ((value_s = el.get_optional<std::string>(
"<xmlattr>.size")))
279 fromtoS = el.get_optional<std::string>(
"<xmlattr>.fromto");
282 Eigen::VectorXd poses = internal::getVectorFromStream<6>(*
fromtoS);
285 Eigen::Vector3d zaxis = poses.tail(3) - poses.head(3);
288 Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitZ(), zaxis).toRotationMatrix();
305 std::vector<std::string> forbiddenListFromTo = {
"plane",
"hfield",
"mesh",
"sphere"};
308 && std::find(forbiddenListFromTo.begin(), forbiddenListFromTo.end(),
geomType)
309 != forbiddenListFromTo.end())
310 throw std::invalid_argument(
311 "fromto tag can only be used with capsules, boxes, cylinders and ellipsoids");
315 size = internal::getVectorFromStream<1>(
sizeS);
317 size = internal::getVectorFromStream<3>(
sizeS);
321 size = internal::getVectorFromStream<3>(
sizeS) * 2;
324 size = Eigen::Vector3d::Zero();
325 size(0) = internal::getVectorFromStream<1>(
sizeS)(0) * 2;
327 Eigen::VectorXd poses = internal::getVectorFromStream<6>(*
fromtoS);
328 Eigen::Vector3d zaxis = poses.tail(3) - poses.head(3);
329 size(2) = zaxis.norm();
335 size = internal::getVectorFromStream<3>(
sizeS);
338 size = Eigen::Vector3d::Zero();
339 size(0) = internal::getVectorFromStream<1>(
sizeS)(0);
341 Eigen::VectorXd poses = internal::getVectorFromStream<6>(*
fromtoS);
342 Eigen::Vector3d zaxis = poses.tail(3) - poses.head(3);
343 size(2) = zaxis.norm() / 2;
349 size = internal::getVectorFromStream<2>(
sizeS);
352 size = Eigen::Vector2d::Zero();
353 size(0) = internal::getVectorFromStream<1>(
sizeS)(0);
354 Eigen::VectorXd poses = internal::getVectorFromStream<6>(*
fromtoS);
355 Eigen::Vector3d zaxis = poses.tail(3) - poses.head(3);
356 size(1) = zaxis.norm() / 2;
362 throw std::invalid_argument(
"geomType does not exist");
398 throw std::invalid_argument(
"Unsupported geometry type");
406 auto name_s = el.get_optional<std::string>(
"<xmlattr>.name");
418 if (
auto geom_p = classE.
classElement.get_child_optional(
"geom"))
423 auto cl_s = el.get_optional<std::string>(
"<xmlattr>.class");
426 std::string className = *cl_s;
428 if (
auto geom_p = classE.
classElement.get_child_optional(
"geom"))
435 throw std::invalid_argument(
"Type is mesh but no mesh file were provided");
447 if (el.get_child_optional(
"<xmlattr>.pos") && el.get_child_optional(
"<xmlattr>.fromto"))
448 throw std::invalid_argument(
"Both pos and fromto are defined in site object");
453 auto fromtoS = el.get_optional<std::string>(
"<xmlattr>.fromto");
456 Eigen::VectorXd poses = internal::getVectorFromStream<6>(*fromtoS);
459 Eigen::Vector3d zaxis = poses.tail(3) - poses.head(3);
462 Eigen::Quaterniond::FromTwoVectors(Eigen::Vector3d::UnitZ(), zaxis).toRotationMatrix();
470 auto name_s = el.get_optional<std::string>(
"<xmlattr>.name");
482 if (
auto site_p = classE.
classElement.get_child_optional(
"site"))
487 auto cl_s = el.get_optional<std::string>(
"<xmlattr>.class");
490 std::string className = *cl_s;
492 if (
auto site_p = classE.
classElement.get_child_optional(
"site"))
505 #ifdef PINOCCHIO_WITH_HPP_FCL
507 meshLoader = std::make_shared<fcl::MeshLoader>(fcl::MeshLoader());
508 #endif // ifdef PINOCCHIO_WITH_HPP_FCL