41 #include <console_bridge/console.h> 
   44 #include <libqhull_r.h> 
   47 #include <boost/math/constants/constants.hpp> 
   52 #include <Eigen/Geometry> 
   53 #include <unordered_map> 
   59 static const double ZERO = 1e-9;
 
   63 static inline double distanceSQR(
const Eigen::Vector3d& p, 
const Eigen::Vector3d& origin, 
const Eigen::Vector3d& dir)
 
   65   Eigen::Vector3d a = p - origin;
 
   66   double d = dir.normalized().dot(a);
 
   67   return a.squaredNorm() - 
d * 
d;
 
   73   intersc(
const Eigen::Vector3d& _pt, 
const double _tm) : 
pt(_pt), 
time(_tm)
 
   80   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
   86   bool operator()(
const intersc& a, 
const intersc& b)
 const 
   88     return a.time < b.time;
 
  101   if (intersections == 
nullptr || ipts.empty())
 
  104   std::sort(ipts.begin(), ipts.end(), interscOrder());
 
  105   const auto n = count > 0 ? std::min<size_t>(count, ipts.size()) : ipts.size();
 
  107   for (
const auto& p : ipts)
 
  109     if (intersections->size() == n)
 
  111     if (!intersections->empty() && p.pt.isApprox(intersections->back(), 
ZERO))
 
  113     intersections->push_back(p.pt);
 
  118 inline Eigen::Vector3d 
normalize(
const Eigen::Vector3d& dir)
 
  120   const double norm = dir.squaredNorm();
 
  121 #if EIGEN_VERSION_AT_LEAST(3, 3, 0) 
  122   return ((norm - 1) > 1e-9) ? (dir / Eigen::numext::sqrt(norm)) : dir;
 
  123 #else  // used in kinetic 
  124   return ((norm - 1) > 1e-9) ? (dir / sqrt(norm)) : dir;
 
  130                                      Eigen::Vector3d& result)
 const 
  134   for (
unsigned int i = 0; i < max_attempts; ++i)
 
  147   return (center_ - p).squaredNorm() <= radius2_;
 
  167   const auto tmpRadiusU = radius_ * scale_ + padding_;
 
  169     throw std::runtime_error(
"Sphere radius must be non-negative.");
 
  170   radiusU_ = tmpRadiusU;
 
  171   radius2_ = radiusU_ * radiusU_;
 
  172   center_ = pose_.translation();
 
  177   auto s = std::allocate_shared<Sphere>(Eigen::aligned_allocator<Sphere>());
 
  178   s->radius_ = radius_;
 
  179   s->padding_ = padding;
 
  182   s->updateInternalData();
 
  188   return 4.0 * boost::math::constants::pi<double>() * radiusU_ * radiusU_ * radiusU_ / 3.0;
 
  199   cylinder.
pose = pose_;
 
  200   cylinder.
radius = radiusU_;
 
  201   cylinder.
length = 2.0 * radiusU_;
 
  209   Eigen::Isometry3d 
transform = Eigen::Isometry3d::Identity();
 
  210   transform.translation() = getPose().translation();
 
  218   Eigen::Isometry3d 
transform = Eigen::Isometry3d::Identity();
 
  219   transform.translation() = getPose().translation();
 
  225                                        Eigen::Vector3d& result)
 const 
  227   for (
unsigned int i = 0; i < max_attempts; ++i)
 
  229     const double minX = center_.x() - radiusU_;
 
  230     const double maxX = center_.x() + radiusU_;
 
  231     const double minY = center_.y() - radiusU_;
 
  232     const double maxY = center_.y() + radiusU_;
 
  233     const double minZ = center_.z() - radiusU_;
 
  234     const double maxZ = center_.z() + radiusU_;
 
  237     for (
int j = 0; j < 20; ++j)
 
  240       if (containsPoint(result))
 
  251   const Eigen::Vector3d dirNorm = 
normalize(dir);
 
  258   Eigen::Vector3d cp = origin - center_;
 
  259   double dpcpv = cp.dot(dirNorm);
 
  261   Eigen::Vector3d w = cp - dpcpv * dirNorm;
 
  262   Eigen::Vector3d Q = center_ + w;
 
  263   double x = radius2_ - w.squaredNorm();
 
  268     double dpQv = w.dot(dirNorm);
 
  272         intersections->push_back(Q);
 
  280     Eigen::Vector3d A = Q - w;
 
  281     Eigen::Vector3d B = Q + w;
 
  283     double dpAv = w.dot(dirNorm);
 
  285     double dpBv = w.dot(dirNorm);
 
  292         intersections->push_back(A);
 
  302         intersections->push_back(B);
 
  314   Eigen::Isometry3d pose = Eigen::Isometry3d::Identity();
 
  315   pose.translation() = sphere.
center;
 
  321   Eigen::Vector3d v = p - center_;
 
  322   double pH = v.dot(normalH_);
 
  324   if (fabs(pH) > length2_)
 
  327   double pB1 = v.dot(normalB1_);
 
  328   double remaining = radius2_ - pB1 * pB1;
 
  334     double pB2 = v.dot(normalB2_);
 
  335     return pB2 * pB2 <= remaining;
 
  347   return { radius_, length_ };
 
  352   return { radiusU_, 2 * length2_ };
 
  357   const auto tmpRadiusU = radius_ * scale_ + padding_;
 
  359     throw std::runtime_error(
"Cylinder radius must be non-negative.");
 
  360   const auto tmpLength2 = scale_ * length_ / 2.0 + padding_;
 
  362     throw std::runtime_error(
"Cylinder length must be non-negative.");
 
  363   radiusU_ = tmpRadiusU;
 
  364   length2_ = tmpLength2;
 
  365   radius2_ = radiusU_ * radiusU_;
 
  366   center_ = pose_.translation();
 
  367   radiusBSqr_ = length2_ * length2_ + radius2_;
 
  368   radiusB_ = sqrt(radiusBSqr_);
 
  371   Eigen::Matrix3d basis = pose_.linear();
 
  372   normalB1_ = basis.col(0);
 
  373   normalB2_ = basis.col(1);
 
  374   normalH_ = basis.col(2);
 
  376   double tmp = -normalH_.dot(center_);
 
  377   d1_ = tmp + length2_;
 
  378   d2_ = tmp - length2_;
 
  382                                          Eigen::Vector3d& result)
 const 
  385   double a = rng.
uniformReal(-boost::math::constants::pi<double>(), boost::math::constants::pi<double>());
 
  387   double x = cos(a) * 
r;
 
  388   double y = sin(a) * 
r;
 
  393   result = pose_ * Eigen::Vector3d(
x, 
y, 
z);
 
  400   auto c = std::allocate_shared<Cylinder>(Eigen::aligned_allocator<Cylinder>());
 
  401   c->length_ = length_;
 
  402   c->radius_ = radius_;
 
  403   c->padding_ = padding;
 
  406   c->updateInternalData();
 
  412   return 2.0 * boost::math::constants::pi<double>() * radius2_ * length2_;
 
  423   cylinder.
pose = pose_;
 
  424   cylinder.
radius = radiusU_;
 
  425   cylinder.
length = 2 * length2_;
 
  434   const auto a = normalH_;
 
  435   const auto e = radiusU_ * (Eigen::Vector3d::Ones() - a.cwiseProduct(a) / a.dot(a)).cwiseSqrt();
 
  436   const auto pa = center_ + length2_ * normalH_;
 
  437   const auto pb = center_ - length2_ * normalH_;
 
  447   bbox.
setPoseAndExtents(getPose(), 2 * Eigen::Vector3d(radiusU_, radiusU_, length2_));
 
  454   const Eigen::Vector3d dirNorm = 
normalize(dir);
 
  459   std::vector<detail::intersc> ipts;
 
  462   double tmp = normalH_.dot(dirNorm);
 
  465     double tmp2 = -normalH_.dot(origin);
 
  466     double t1 = (tmp2 - d1_) / tmp;
 
  470       Eigen::Vector3d p1(origin + dirNorm * t1);
 
  471       Eigen::Vector3d v1(p1 - center_);
 
  472       v1 = v1 - normalH_.dot(v1) * normalH_;
 
  475         if (intersections == 
nullptr)
 
  483     double t2 = (tmp2 - d2_) / tmp;
 
  486       Eigen::Vector3d p2(origin + dirNorm * t2);
 
  487       Eigen::Vector3d v2(p2 - center_);
 
  488       v2 = v2 - normalH_.dot(v2) * normalH_;
 
  491         if (intersections == 
nullptr)
 
  503     Eigen::Vector3d VD(normalH_.cross(dirNorm));
 
  504     Eigen::Vector3d ROD(normalH_.cross(origin - center_));
 
  505     double a = VD.squaredNorm();
 
  506     double b = 2.0 * ROD.dot(VD);
 
  507     double c = ROD.squaredNorm() - radius2_;
 
  508     double d = b * b - 4.0 * a * c;
 
  513       double t1 = (b + 
d) / e;
 
  514       double t2 = (b - 
d) / e;
 
  518         Eigen::Vector3d p1(origin + dirNorm * t1);
 
  519         Eigen::Vector3d v1(center_ - p1);
 
  523           if (intersections == 
nullptr)
 
  533         Eigen::Vector3d p2(origin + dirNorm * t2);
 
  534         Eigen::Vector3d v2(center_ - p2);
 
  538           if (intersections == 
nullptr)
 
  565                                     Eigen::Vector3d& result)
 const 
  567   result = pose_ * Eigen::Vector3d(rng.
uniformReal(-length2_, length2_), rng.
uniformReal(-width2_, width2_),
 
  574   const Eigen::Vector3d aligned = (invRot_ * (p - center_)).cwiseAbs();
 
  575   return aligned[0] <= length2_ && aligned[1] <= width2_ && aligned[2] <= height2_;
 
  580   const double* size = 
static_cast<const shapes::Box*
>(shape)->size;
 
  588   return { length_, width_, height_ };
 
  593   return { 2 * length2_, 2 * width2_, 2 * height2_ };
 
  598   double s2 = scale_ / 2.0;
 
  599   const auto tmpLength2 = length_ * s2 + padding_;
 
  600   const auto tmpWidth2 = width_ * s2 + padding_;
 
  601   const auto tmpHeight2 = height_ * s2 + padding_;
 
  603   if (tmpLength2 < 0 || tmpWidth2 < 0 || tmpHeight2 < 0)
 
  604     throw std::runtime_error(
"Box dimensions must be non-negative.");
 
  606   length2_ = tmpLength2;
 
  608   height2_ = tmpHeight2;
 
  610   center_ = pose_.translation();
 
  612   radius2_ = length2_ * length2_ + width2_ * width2_ + height2_ * height2_;
 
  613   radiusB_ = sqrt(radius2_);
 
  616   invRot_ = pose_.linear().transpose();
 
  619   const Eigen::Vector3d tmp(length2_, width2_, height2_);
 
  620   minCorner_ = center_ - tmp;
 
  621   maxCorner_ = center_ + tmp;
 
  624 std::shared_ptr<bodies::Body> 
bodies::Box::cloneAt(
const Eigen::Isometry3d& pose, 
double padding, 
double scale)
 const 
  626   auto b = std::allocate_shared<Box>(Eigen::aligned_allocator<Box>());
 
  627   b->length_ = length_;
 
  629   b->height_ = height_;
 
  630   b->padding_ = padding;
 
  633   b->updateInternalData();
 
  639   return 8.0 * length2_ * width2_ * height2_;
 
  652   if (length2_ > width2_ && length2_ > height2_)
 
  654     cylinder.
length = length2_ * 2.0;
 
  657     Eigen::Isometry3d rot(Eigen::AngleAxisd(90.0
f * (
M_PI / 180.0
f), Eigen::Vector3d::UnitY()));
 
  658     cylinder.
pose = pose_ * rot;
 
  660   else if (width2_ > height2_)
 
  662     cylinder.
length = width2_ * 2.0;
 
  665     cylinder.
radius = sqrt(height2_ * height2_ + length2_ * length2_);
 
  666     Eigen::Isometry3d rot(Eigen::AngleAxisd(90.0
f * (
M_PI / 180.0
f), Eigen::Vector3d::UnitX()));
 
  667     cylinder.
pose = pose_ * rot;
 
  671     cylinder.
length = height2_ * 2.0;
 
  674     cylinder.
pose = pose_;
 
  676   cylinder.
radius = sqrt(a * a + b * b);
 
  688   bbox.
setPoseAndExtents(getPose(), 2 * Eigen::Vector3d(length2_, width2_, height2_));
 
  695   const Eigen::Vector3d dirNorm = 
normalize(dir);
 
  701   const Eigen::Vector3d o(invRot_ * (origin - center_) + center_);
 
  702   const Eigen::Vector3d 
d(invRot_ * dirNorm);
 
  704   Eigen::Vector3d tmpTmin, tmpTmax;
 
  705   tmpTmin = (minCorner_ - o).cwiseQuotient(
d);
 
  706   tmpTmax = (maxCorner_ - o).cwiseQuotient(
d);
 
  710   for (
size_t i = 0; i < 3; ++i)
 
  713       std::swap(tmpTmin[i], tmpTmax[i]);
 
  723   tmin = std::fmax(tmpTmin.x(), std::fmax(tmpTmin.y(), tmpTmin.z()));
 
  724   tmax = std::fmin(tmpTmax.x(), std::fmin(tmpTmax.y(), tmpTmax.z()));
 
  743         intersections->push_back(tmin * dirNorm + origin);
 
  744         if (count == 0 || count > 1)
 
  745           intersections->push_back(tmax * dirNorm + origin);
 
  751         intersections->push_back(tmax * dirNorm + origin);
 
  757       intersections->push_back(tmax * dirNorm + origin);
 
  770   Eigen::Isometry3d pose = Eigen::Isometry3d::Identity();
 
  771   pose.translation() = 
aabb.center();
 
  790   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  798   if (bounding_box_.containsPoint(p))
 
  801     Eigen::Vector3d ip(i_pose_ * p);
 
  802     return isPointInsidePlanes(ip);
 
  810   for (
unsigned int i = 0; i < mesh_data_->triangles_.size(); i += 3)
 
  813         mesh_data_->vertices_[mesh_data_->triangles_[i]] - mesh_data_->vertices_[mesh_data_->triangles_[i + 1]];
 
  815         mesh_data_->vertices_[mesh_data_->triangles_[i]] - mesh_data_->vertices_[mesh_data_->triangles_[i + 2]];
 
  817     Eigen::Vector3d tri_normal = d1.cross(d2);
 
  818     tri_normal.normalize();
 
  820     Eigen::Vector3d normal(mesh_data_->planes_[mesh_data_->plane_for_triangle_[i / 3]].x(),
 
  821                            mesh_data_->planes_[mesh_data_->plane_for_triangle_[i / 3]].y(),
 
  822                            mesh_data_->planes_[mesh_data_->plane_for_triangle_[i / 3]].z());
 
  823     bool same_dir = tri_normal.dot(normal) > 0;
 
  826       std::swap(mesh_data_->triangles_[i], mesh_data_->triangles_[i + 1]);
 
  833   mesh_data_ = std::allocate_shared<MeshData>(Eigen::aligned_allocator<MeshData>());
 
  836   double maxX = -std::numeric_limits<double>::infinity(), maxY = -std::numeric_limits<double>::infinity(),
 
  837          maxZ = -std::numeric_limits<double>::infinity();
 
  838   double minX = std::numeric_limits<double>::infinity(), minY = std::numeric_limits<double>::infinity(),
 
  839          minZ = std::numeric_limits<double>::infinity();
 
  844     double vy = mesh->
vertices[3 * i + 1];
 
  845     double vz = mesh->
vertices[3 * i + 2];
 
  869   mesh_data_->box_size_ = Eigen::Vector3d(maxX - minX, maxY - minY, maxZ - minZ);
 
  871   mesh_data_->box_offset_ = Eigen::Vector3d((minX + maxX) / 2.0, (minY + maxY) / 2.0, (minZ + maxZ) / 2.0);
 
  873   mesh_data_->planes_.clear();
 
  874   mesh_data_->triangles_.clear();
 
  875   mesh_data_->vertices_.clear();
 
  876   mesh_data_->mesh_radiusB_ = 0.0;
 
  877   mesh_data_->mesh_center_ = Eigen::Vector3d();
 
  879   double xdim = maxX - minX;
 
  880   double ydim = maxY - minY;
 
  881   double zdim = maxZ - minZ;
 
  891   double maxdist = -std::numeric_limits<double>::infinity();
 
  892   if (xdim > ydim && xdim > zdim)
 
  896     pose1 = mesh_data_->box_offset_.y();
 
  897     pose2 = mesh_data_->box_offset_.z();
 
  900   else if (ydim > zdim)
 
  904     pose1 = mesh_data_->box_offset_.x();
 
  905     pose2 = mesh_data_->box_offset_.z();
 
  912     pose1 = mesh_data_->box_offset_.x();
 
  913     pose2 = mesh_data_->box_offset_.y();
 
  918   coordT* points = (coordT*)calloc(mesh->
vertex_count * 3, 
sizeof(coordT));
 
  921     points[3 * i + 0] = (coordT)mesh->
vertices[3 * i + 0];
 
  922     points[3 * i + 1] = (coordT)mesh->
vertices[3 * i + 1];
 
  923     points[3 * i + 2] = (coordT)mesh->
vertices[3 * i + 2];
 
  925     double dista = mesh->
vertices[3 * i + off1] - pose1;
 
  926     double distb = mesh->
vertices[3 * i + off2] - pose2;
 
  927     double dist = sqrt(((dista * dista) + (distb * distb)));
 
  931   mesh_data_->bounding_cylinder_.radius = maxdist;
 
  932   mesh_data_->bounding_cylinder_.length = cyl_length;
 
  934   static FILE* 
null = fopen(
"/dev/null", 
"w");
 
  936   char flags[] = 
"qhull Tv Qt";
 
  941   int exitcode = qh_new_qhull(qh, 3, mesh->
vertex_count, points, 
true, flags, 
null, 
null);
 
  945     CONSOLE_BRIDGE_logWarn(
"Convex hull creation failed");
 
  946     qh_freeqhull(qh, !qh_ALL);
 
  947     int curlong, totlong;
 
  948     qh_memfreeshort(qh, &curlong, &totlong);
 
  952   int num_facets = qh->num_facets;
 
  954   int num_vertices = qh->num_vertices;
 
  955   mesh_data_->vertices_.reserve(num_vertices);
 
  956   Eigen::Vector3d sum(0, 0, 0);
 
  959   std::map<unsigned int, unsigned int> qhull_vertex_table;
 
  963     Eigen::Vector3d vert(vertex->point[0], vertex->point[1], vertex->point[2]);
 
  964     qhull_vertex_table[vertex->id] = mesh_data_->vertices_.size();
 
  966     mesh_data_->vertices_.push_back(vert);
 
  969   mesh_data_->mesh_center_ = sum / (double)(num_vertices);
 
  970   for (
unsigned int j = 0; j < mesh_data_->vertices_.size(); ++j)
 
  972     double dist = (mesh_data_->vertices_[j] - mesh_data_->mesh_center_).squaredNorm();
 
  973     if (dist > mesh_data_->mesh_radiusB_)
 
  974       mesh_data_->mesh_radiusB_ = dist;
 
  977   mesh_data_->mesh_radiusB_ = sqrt(mesh_data_->mesh_radiusB_);
 
  978   mesh_data_->triangles_.reserve(num_facets);
 
  984     Eigen::Vector4d planeEquation(facet->normal[0], facet->normal[1], facet->normal[2], facet->offset);
 
  985     if (!mesh_data_->planes_.empty())
 
  988       if ((planeEquation - mesh_data_->planes_.back()).cwiseAbs().maxCoeff() > 1e-6)  
 
  989         mesh_data_->planes_.push_back(planeEquation);
 
  993       mesh_data_->planes_.push_back(planeEquation);
 
  997     int vertex_n, vertex_i;
 
  998     FOREACHvertex_i_(qh, (*facet).vertices)
 
 1000       mesh_data_->triangles_.push_back(qhull_vertex_table[vertex->id]);
 
 1003     mesh_data_->plane_for_triangle_[(mesh_data_->triangles_.size() - 1) / 3] = mesh_data_->planes_.size() - 1;
 
 1004     mesh_data_->triangle_for_plane_[mesh_data_->planes_.size() - 1] = (mesh_data_->triangles_.size() - 1) / 3;
 
 1006   qh_freeqhull(qh, !qh_ALL);
 
 1007   int curlong, totlong;
 
 1008   qh_memfreeshort(qh, &curlong, &totlong);
 
 1024   if (padding_ == 0.0 && scale_ == 1.0)
 
 1026     scaled_vertices_ = &mesh_data_->vertices_;
 
 1030   if (!scaled_vertices_storage_)
 
 1032   scaled_vertices_ = scaled_vertices_storage_.get();
 
 1033   scaled_vertices_storage_->resize(mesh_data_->vertices_.size());
 
 1039   std::map<unsigned int, std::vector<unsigned int>> vertex_to_tris;
 
 1040   for (
unsigned int i = 0; i < mesh_data_->triangles_.size() / 3; ++i)
 
 1042     vertex_to_tris[mesh_data_->triangles_[3 * i + 0]].push_back(i);
 
 1043     vertex_to_tris[mesh_data_->triangles_[3 * i + 1]].push_back(i);
 
 1044     vertex_to_tris[mesh_data_->triangles_[3 * i + 2]].push_back(i);
 
 1047   for (
unsigned int i = 0; i < mesh_data_->vertices_.size(); ++i)
 
 1049     Eigen::Vector3d v(mesh_data_->vertices_[i] - mesh_data_->mesh_center_);
 
 1051     for (
unsigned int t : vertex_to_tris[i])
 
 1053       const Eigen::Vector4d& plane = mesh_data_->planes_[mesh_data_->plane_for_triangle_[t]];
 
 1054       Eigen::Vector3d plane_normal(plane.x(), plane.y(), plane.z());
 
 1055       double d_scaled_padded =
 
 1056           scale_ * plane.w() - (1 - scale_) * mesh_data_->mesh_center_.dot(plane_normal) - padding_;
 
 1059       double denom = v.dot(plane_normal);
 
 1060       if (fabs(denom) < 1e-3)
 
 1062       double lambda = (-mesh_data_->mesh_center_.dot(plane_normal) - d_scaled_padded) / denom;
 
 1063       Eigen::Vector3d vert_on_plane = v * lambda + mesh_data_->mesh_center_;
 
 1064       projected_vertices.push_back(vert_on_plane);
 
 1066     if (projected_vertices.empty())
 
 1068       double l = v.norm();
 
 1069       scaled_vertices_storage_->at(i) =
 
 1070           mesh_data_->mesh_center_ + v * (scale_ + (l > 
detail::ZERO ? padding_ / l : 0.0));
 
 1074       Eigen::Vector3d sum(0, 0, 0);
 
 1075       for (
const Eigen::Vector3d& vertex : projected_vertices)
 
 1079       sum /= projected_vertices.size();
 
 1080       scaled_vertices_storage_->at(i) = sum;
 
 1089   Eigen::Isometry3d pose = pose_;
 
 1090   pose.translation() = Eigen::Vector3d(pose_ * mesh_data_->box_offset_);
 
 1092   shapes::Box box_shape(mesh_data_->box_size_.x(), mesh_data_->box_size_.y(), mesh_data_->box_size_.z());
 
 1093   bounding_box_.setPoseDirty(pose);
 
 1096   bounding_box_.setPaddingDirty(padding_);
 
 1097   bounding_box_.setScaleDirty(scale_);
 
 1098   bounding_box_.setDimensionsDirty(&box_shape);
 
 1099   bounding_box_.updateInternalData();
 
 1101   i_pose_ = pose_.inverse();
 
 1102   center_ = pose_ * mesh_data_->mesh_center_;
 
 1103   radiusB_ = mesh_data_->mesh_radiusB_ * scale_ + padding_;
 
 1104   radiusBSqr_ = radiusB_ * radiusB_;
 
 1107   if (padding_ == 0.0 && scale_ == 1.0)
 
 1108     scaled_vertices_ = &mesh_data_->vertices_;
 
 1111     if (!scaled_vertices_storage_)
 
 1113     scaled_vertices_ = scaled_vertices_storage_.get();
 
 1114     scaled_vertices_storage_->resize(mesh_data_->vertices_.size());
 
 1115     for (
unsigned int i = 0; i < mesh_data_->vertices_.size(); ++i)
 
 1117       Eigen::Vector3d v(mesh_data_->vertices_[i] - mesh_data_->mesh_center_);
 
 1118       double l = v.norm();
 
 1119       scaled_vertices_storage_->at(i) =
 
 1120           mesh_data_->mesh_center_ + v * (scale_ + (l > 
detail::ZERO ? padding_ / l : 0.0));
 
 1126   static const std::vector<unsigned int> empty;
 
 1127   return mesh_data_ ? mesh_data_->triangles_ : empty;
 
 1133   return mesh_data_ ? mesh_data_->vertices_ : empty;
 
 1138   return scaled_vertices_ ? *scaled_vertices_ : getVertices();
 
 1144   return mesh_data_ ? mesh_data_->planes_ : empty;
 
 1150   auto m = std::allocate_shared<ConvexMesh>(Eigen::aligned_allocator<ConvexMesh>());
 
 1151   m->mesh_data_ = mesh_data_;
 
 1152   m->padding_ = padding;
 
 1155   m->updateInternalData();
 
 1162   sphere.
radius = radiusB_;
 
 1168   cylinder.
length = mesh_data_ ? mesh_data_->bounding_cylinder_.length * scale_ + 2 * padding_ : 0.0;
 
 1169   cylinder.
radius = mesh_data_ ? mesh_data_->bounding_cylinder_.radius * scale_ + padding_ : 0.0;
 
 1172   bounding_box_.computeBoundingCylinder(cyl);
 
 1180   bounding_box_.computeBoundingBox(bbox);
 
 1185   bounding_box_.computeBoundingBox(bbox);
 
 1190   unsigned int numplanes = mesh_data_->planes_.size();
 
 1191   for (
unsigned int i = 0; i < numplanes; ++i)
 
 1193     const Eigen::Vector4d& plane = mesh_data_->planes_[i];
 
 1194     Eigen::Vector3d plane_vec(plane.x(), plane.y(), plane.z());
 
 1198     const auto scaled_point_on_plane =
 
 1199         scaled_vertices_->at(mesh_data_->triangles_[3 * mesh_data_->triangle_for_plane_[i]]);
 
 1200     const double w_scaled_padded = -plane_vec.dot(scaled_point_on_plane);
 
 1210   unsigned int numvertices = mesh_data_->vertices_.size();
 
 1211   unsigned int result = 0;
 
 1212   for (
unsigned int i = 0; i < numvertices; ++i)
 
 1214     Eigen::Vector3d plane_vec(planeNormal.x(), planeNormal.y(), planeNormal.z());
 
 1215     double dist = plane_vec.dot(mesh_data_->vertices_[i]) + planeNormal.w() - 1e-6;
 
 1224   double volume = 0.0;
 
 1226     for (
unsigned int i = 0; i < mesh_data_->triangles_.size() / 3; ++i)
 
 1228       const Eigen::Vector3d& v1 = mesh_data_->vertices_[mesh_data_->triangles_[3 * i + 0]];
 
 1229       const Eigen::Vector3d& v2 = mesh_data_->vertices_[mesh_data_->triangles_[3 * i + 1]];
 
 1230       const Eigen::Vector3d& v3 = mesh_data_->vertices_[mesh_data_->triangles_[3 * i + 2]];
 
 1231       volume += v1.x() * v2.y() * v3.z() + v2.x() * v3.y() * v1.z() + v3.x() * v1.y() * v2.z() -
 
 1232                 v1.x() * v3.y() * v2.z() - v2.x() * v1.y() * v3.z() - v3.x() * v2.y() * v1.z();
 
 1234   return fabs(volume) / 6.0;
 
 1241   const Eigen::Vector3d dirNorm = 
normalize(dir);
 
 1247   if (!bounding_box_.intersectsRay(origin, dirNorm))
 
 1251   Eigen::Vector3d orig(i_pose_ * origin);
 
 1252   Eigen::Vector3d dr(i_pose_.linear() * dirNorm);
 
 1254   std::vector<detail::intersc> ipts;
 
 1256   bool result = 
false;
 
 1259   const auto nt = mesh_data_->triangles_.size() / 3;
 
 1260   for (
size_t i = 0; i < nt; ++i)
 
 1262     Eigen::Vector3d vec(mesh_data_->planes_[mesh_data_->plane_for_triangle_[i]].x(),
 
 1263                         mesh_data_->planes_[mesh_data_->plane_for_triangle_[i]].y(),
 
 1264                         mesh_data_->planes_[mesh_data_->plane_for_triangle_[i]].z());
 
 1266     const double tmp = vec.dot(dr);
 
 1270       const double w_scaled_padded = vec.dot(scaled_vertices_->at(mesh_data_->triangles_[3 * i]));
 
 1271       const double t = -(vec.dot(orig) + w_scaled_padded) / tmp;
 
 1274         const auto i3 = 3 * i;
 
 1275         const auto v1 = mesh_data_->triangles_[i3 + 0];
 
 1276         const auto v2 = mesh_data_->triangles_[i3 + 1];
 
 1277         const auto v3 = mesh_data_->triangles_[i3 + 2];
 
 1279         const Eigen::Vector3d& a = scaled_vertices_->at(v1);
 
 1280         const Eigen::Vector3d& b = scaled_vertices_->at(v2);
 
 1281         const Eigen::Vector3d& c = scaled_vertices_->at(v3);
 
 1283         Eigen::Vector3d cb(c - b);
 
 1284         Eigen::Vector3d ab(a - b);
 
 1287         Eigen::Vector3d P(orig + dr * t);
 
 1290         Eigen::Vector3d pb(P - b);
 
 1291         Eigen::Vector3d c1(cb.cross(pb));
 
 1292         Eigen::Vector3d c2(cb.cross(ab));
 
 1293         if (c1.dot(c2) < 0.0)
 
 1296         Eigen::Vector3d ca(c - a);
 
 1297         Eigen::Vector3d pa(P - a);
 
 1298         Eigen::Vector3d ba(-ab);
 
 1302         if (c1.dot(c2) < 0.0)
 
 1308         if (c1.dot(c2) < 0.0)
 
 1323   if (result && intersections)
 
 1340   for (
unsigned int i = 0; i < 
shapes.size(); i++)
 
 1341     addBody(
shapes[i], poses[i], padding);
 
 1351   for (
auto& body : bodies_)
 
 1358   bodies_.push_back(body);
 
 1374   return bodies_.size();
 
 1379   if (i >= bodies_.size())
 
 1385   bodies_[i]->setPose(pose);
 
 1390   if (i >= bodies_.size())
 
 1401   for (std::size_t i = 0; i < bodies_.size(); ++i)
 
 1402     if (bodies_[i]->containsPoint(p, 
verbose))
 
 1413   return containsPoint(p, dummy, 
verbose);
 
 1419   for (std::size_t i = 0; i < bodies_.size(); ++i)
 
 1420     if (bodies_[i]->intersectsRay(origin, dir, intersections, count))