39 #ifndef FCL_SHAPE_CONVEX_INL_H 
   40 #define FCL_SHAPE_CONVEX_INL_H 
   61     const std::shared_ptr<
const std::vector<
Vector3<S>>>& vertices,
 
   62     int num_faces, 
const std::shared_ptr<
const std::vector<int>>& faces,
 
   63     bool throw_if_invalid)
 
   66       num_faces_(num_faces),
 
   68       throw_if_invalid_(throw_if_invalid),
 
   69       find_extreme_via_neighbors_{vertices->size() >
 
   70                                   kMinVertCountForEdgeWalking} {
 
   71   assert(vertices != 
nullptr);
 
   72   assert(faces != 
nullptr);
 
   76   for (
const auto& vertex : *vertices_) {
 
   79   interior_point_ = sum * (S)(1.0 / vertices_->size());
 
   80   FindVertexNeighbors();
 
   81   ValidateMesh(throw_if_invalid);
 
   90   for (
const auto& v : *vertices_) {
 
   91     this->aabb_local += v;
 
   94   this->aabb_center = this->aabb_local.center();
 
   95   this->aabb_radius = (this->aabb_local.min_ - this->aabb_center).norm();
 
  110 template <
typename S>
 
  112   const std::vector<Vector3<S>>& vertices = *vertices_;
 
  113   const std::vector<int>& faces = *faces_;
 
  117   C_canonical << 1/ 60.0, 1/120.0, 1/120.0,
 
  118       1/120.0, 1/ 60.0, 1/120.0,
 
  119       1/120.0, 1/120.0, 1/ 60.0;
 
  123   for (
int i = 0; i < num_faces_; ++i) {
 
  124     const int vertex_count = faces[face_index];
 
  128     for (
int j = 1; j <= vertex_count; ++j) {
 
  129       face_center += vertices[faces[face_index + j]];
 
  131     face_center = face_center * (1.0 / vertex_count);
 
  136     const int vertex_base = face_index + 1;
 
  137     for (
int j = 0; j < vertex_count; ++j) {
 
  138       int e_first = faces[vertex_base + j];
 
  139       int e_second = faces[vertex_base + (j + 1) % vertex_count];
 
  142       S d_six_vol = (v1.cross(v2)).dot(v3);
 
  147       C += A.transpose() * C_canonical * A * d_six_vol; 
 
  148       vol_times_six += d_six_vol;
 
  151     face_index += vertex_count + 1;
 
  154   S trace_C = C(0, 0) + C(1, 1) + C(2, 2);
 
  157   m << trace_C - C(0, 0), -C(0, 1), -C(0, 2),
 
  158       -C(1, 0), trace_C - C(1, 1), -C(1, 2),
 
  159       -C(2, 0), -C(2, 1), trace_C - C(2, 2);
 
  161   return m * (6 / vol_times_six);
 
  165 template <
typename S>
 
  167   const std::vector<Vector3<S>>& vertices = *vertices_;
 
  168   const std::vector<int>& faces = *faces_;
 
  172   for (
int i = 0; i < num_faces_; ++i) {
 
  173     const int vertex_count = faces[face_index];
 
  180     for (
int j = 1; j <= vertex_count; ++j) {
 
  181       face_center += vertices[faces[face_index + j]];
 
  183     face_center = face_center * (1.0 / vertex_count);
 
  188     for (
int j = 1; j <= vertex_count; ++j) {
 
  189       int e_first = faces[face_index + j];
 
  190       int e_second = faces[face_index + (j % vertex_count) + 1];
 
  193       S d_six_vol = (v1.cross(v2)).dot(v3);
 
  195       com += (v1 + v2 + face_center) * d_six_vol;
 
  198     face_index += vertex_count + 1;
 
  201   return com / (vol * 4); 
 
  206   const std::vector<Vector3<S>>& vertices = *vertices_;
 
  207   const std::vector<int>& faces = *faces_;
 
  210   for (
int i = 0; i < num_faces_; ++i) {
 
  211     const int vertex_count = faces[face_index];
 
  222     for (
int j = 1; j <= vertex_count; ++j) {
 
  223       face_center += vertices[faces[face_index + j]];
 
  225     face_center = face_center * (1.0 / vertex_count);
 
  235     for (
int j = 1; j <= vertex_count; ++j) {
 
  236       int e_first = faces[face_index + j];
 
  237       int e_second = faces[face_index + (j % vertex_count) + 1];
 
  240       S d_six_vol = (v1.cross(v2)).dot(v3);
 
  244     face_index += vertex_count + 1;
 
  251 template <
typename S>
 
  254   std::vector<Vector3<S>> result;
 
  255   result.reserve(vertices_->size());
 
  257   for (
const auto& v : *vertices_) {
 
  258     result.push_back(tf * v);
 
  265 template <
typename S>
 
  270   const std::vector<Vector3<S>>& vertices = *vertices_;
 
  274   std::vector<int8_t> visited(vertices.size(), 0);
 
  275   int extreme_index = 0;
 
  276   S extreme_value = v_C.dot(vertices[extreme_index]);
 
  278   if (find_extreme_via_neighbors_) {
 
  279     bool keep_searching = 
true;
 
  280     while (keep_searching) {
 
  281       keep_searching = 
false;
 
  282       const int neighbor_start = neighbors_[extreme_index];
 
  283       const int neighbor_count = neighbors_[neighbor_start];
 
  284       for (
int n_index = neighbor_start + 1;
 
  285            n_index <= neighbor_start + neighbor_count; ++n_index) {
 
  286         const int neighbor_index = neighbors_[n_index];
 
  287         if (visited[neighbor_index]) 
continue;
 
  288         visited[neighbor_index] = 1;
 
  289         const S neighbor_value = v_C.dot(vertices[neighbor_index]);
 
  296         if (neighbor_value >= extreme_value) {
 
  297           keep_searching = 
true;
 
  298           extreme_index = neighbor_index;
 
  299           extreme_value = neighbor_value;
 
  305     for (
int i = 1; i < static_cast<int>(vertices.size()); ++i) {
 
  306       S value = v_C.dot(vertices[i]);
 
  307       if (value > extreme_value) {
 
  309         extreme_value = value;
 
  313   return vertices[extreme_index];
 
  317 template <
typename S>
 
  320   std::stringstream ss;
 
  321   ss << std::setprecision(precision);
 
  322   ss << 
"Convex<" << S_str << 
">(" 
  323      << 
"\n  std::make_shared<std::vector<Vector3<" << S_str << 
">>>(" 
  324      << 
"\n    std::initializer_list<Vector3<" << S_str << 
">>{";
 
  326     ss << 
"\n      Vector3<" << S_str << 
">(" << p_GV[0] << 
", " << p_GV[1]
 
  327        << 
", " << p_GV[2] << 
"),";
 
  330   ss << 
"\n    " << num_faces_ << 
",";
 
  331   ss << 
"\n    std::make_shared<std::vector<int>>(" 
  332      << 
"\n        std::initializer_list<int>{" 
  334   const std::vector<int>& faces = *faces_;
 
  336   for (
int i = 0; i < num_faces_; ++i) {
 
  337     const int vertex_count = faces[face_index];
 
  338     ss << 
" " << vertex_count << 
",";
 
  339     for (
int j = 1; j <= vertex_count; ++j) {
 
  340       ss << 
" " << faces[face_index + j] << 
",";
 
  342     face_index += vertex_count + 1;
 
  345      << 
"\n    " << std::boolalpha << throw_if_invalid_ << 
");";
 
  351 template <
typename S>
 
  353   ValidateTopology(throw_on_error);
 
  359 template <
typename S>
 
  362   assert(neighbors_.size() > vertices_->size());
 
  364   std::stringstream ss;
 
  365   ss << 
"Found errors in the Convex mesh:";
 
  369   auto make_edge = [](
int v0, 
int v1) {
 
  371       return std::make_pair(v0, v1);
 
  374   bool all_connected = 
true;
 
  377   std::map<std::pair<int, int>, 
int> per_edge_face_count;
 
  379   for (
int v = 0; v < static_cast<int>(vertices_->size()); ++v) {
 
  380     const int neighbor_start = neighbors_[v];
 
  381     const int neighbor_count = neighbors_[neighbor_start];
 
  382     if (neighbor_count == 0) {
 
  384         ss << 
"\n Not all vertices are connected.";
 
  385         all_connected = 
false;
 
  387       ss << 
"\n  Vertex " << v << 
" is not included in any faces.";
 
  389     for (
int n_index = neighbor_start + 1;
 
  390          n_index <= neighbor_start + neighbor_count; ++n_index) {
 
  391       const int n = neighbors_[n_index];
 
  392         per_edge_face_count[make_edge(v, n)] = 0;
 
  400   const std::vector<int>& faces = *faces_;
 
  402   for (
int f = 0; f < num_faces_; ++f) {
 
  403       const int vertex_count = faces[face_index];
 
  404       int prev_v = faces[face_index + vertex_count];
 
  405       for (
int i = face_index + 1; i <= face_index + vertex_count; ++i) {
 
  406           const int v = faces[i];
 
  407           ++per_edge_face_count[make_edge(v, prev_v)];
 
  410       face_index += vertex_count + 1;
 
  414   bool is_watertight = 
true;
 
  415   for (
const auto& key_value_pair : per_edge_face_count) {
 
  416     const auto& edge = key_value_pair.first;
 
  417     const int count = key_value_pair.second;
 
  420         is_watertight = 
false;
 
  421         ss << 
"\n The mesh is not watertight.";
 
  423       ss << 
"\n  Edge between vertices " << edge.first << 
" and " << edge.second
 
  424          << 
" is shared by " << count << 
" faces (should be 2).";
 
  428   const bool has_error = !(is_watertight && all_connected);
 
  432   find_extreme_via_neighbors_ = find_extreme_via_neighbors_ && !has_error;
 
  433   if (has_error && throw_on_error) {
 
  434     throw std::runtime_error(ss.str());
 
  439 template <
typename S>
 
  445   const int v_count = 
static_cast<int>(vertices_->size());
 
  446   std::vector<std::set<int>> neighbors(v_count);
 
  447   const std::vector<int>& faces = *faces_;
 
  449   for (
int f = 0; f < num_faces_; ++f) {
 
  450     const int vertex_count = faces[face_index];
 
  451     int prev_v = faces[face_index + vertex_count];
 
  452     for (
int i = face_index + 1; i <= face_index + vertex_count; ++i) {
 
  453       const int v = faces[i];
 
  454       neighbors[v].insert(prev_v);
 
  455       neighbors[prev_v].insert(v);
 
  458     face_index += vertex_count + 1;
 
  462   neighbors_.resize(v_count);
 
  463   for (
int v = 0; v < v_count; ++v) {
 
  464     const std::set<int>& v_neighbors = neighbors[v];
 
  465     neighbors_[v] = 
static_cast<int>(neighbors_.size());
 
  466     neighbors_.push_back(
static_cast<int>(v_neighbors.size()));
 
  467     neighbors_.insert(neighbors_.end(), v_neighbors.begin(), v_neighbors.end());