Mn::Trade::MeshData buildTrajectoryTubeSolid()

in src/esp/geo/Geo.cpp [269:507]


Mn::Trade::MeshData buildTrajectoryTubeSolid(
    const std::vector<Mn::Vector3>& pts,
    const std::vector<Mn::Color3>& interpColors,
    int numSegments,
    float radius,
    bool smooth,
    int numInterp,
    ColorSpace clrSpace) {
  // 1. Build smoothed trajectory through passed points if requested
  // points in trajectory
  // A centripetal CR spline (alpha == .5) will not have cusps, while remaining
  // true to underlying key point trajectory.
  float alpha = .5;
  std::vector<Mn::Vector3> trajectory =
      smooth ? buildCatmullRomTrajOfPoints(pts, numInterp, alpha) : pts;

  // size of trajectory
  const Mn::UnsignedInt trajSize = trajectory.size();

  // 2. Build list of interpolating colors for each ring of trajectory.
  // want to evenly interpolate between colors provided
  const Mn::UnsignedInt numColors = interpColors.size();
  std::vector<Mn::Vector3> trajColors;

  if (numColors == 1) {
    trajColors.reserve(trajSize);
    // with only 1 color, just make duplicates of color for every trajectory
    // point/vertex
    for (const auto& pt : trajectory) {
      trajColors.emplace_back(
          convertClrToInterpClrVector(interpColors[0], clrSpace));
    }

  } else {
    // interpolate in hsv space - first convert src colors to HSV
    std::vector<Mn::Vector3> srcClrs;
    srcClrs.reserve(numColors);
    for (const auto& clr : interpColors) {
      srcClrs.emplace_back(convertClrToInterpClrVector(clr, clrSpace));
    }
    // determine how many interpolations we should have : trajColors should be
    // trajSize in size
    int numClrInterp = (trajSize / (numColors - 1)) + 1;
    // now build interpolated vector of colors
    trajColors = buildCatmullRomTrajOfPoints(srcClrs, numClrInterp, alpha);
    // fill end of trajColors array with final color if smaller than size of
    // trajectory
    while (trajColors.size() < trajSize) {
      trajColors.push_back(trajColors.back());
    }
  }

  // 3. Build mesh vertex points around each trajectory point at appropriate
  // distance (radius). For each point in trajectory, add a wireframe circle
  // centered at that point, appropriately oriented based on tangents

  Cr::Containers::Array<Magnum::Vector3> circleVerts =
      Mn::Primitives::circle3DWireframe(numSegments).positions3DAsArray();
  // normalized verts will provide vert normals.
  Cr::Containers::Array<Magnum::Vector3> circleNormVerts{
      Cr::NoInit, sizeof(Magnum::Vector3) * numSegments};

  // transform points to be on circle of given radius, and make copy to
  // normalize points
  for (int i = 0; i < numSegments; ++i) {
    circleVerts[i] *= radius;
    circleNormVerts[i] = circleVerts[i].normalized();
  }

  // # of vertices in resultant tube == # circle verts * # points in trajectory
  const Mn::UnsignedInt vertexCount = numSegments * trajSize + 2;
  // a function-local struct representing a vertex
  struct Vertex {
    Mn::Vector3 position;
    Mn::Vector3 normal;
    // vertex color default to white
    Mn::Color3ub color = 0xffffff_rgb;
  };

  // Vertex data storage
  Cr::Containers::Array<char> vertexData{Cr::NoInit,
                                         sizeof(Vertex) * vertexCount};
  // Cast memory to be a strided array so it can be accessed via slices.
  Cr::Containers::StridedArrayView1D<Vertex> vertices =
      Cr::Containers::arrayCast<Vertex>(vertexData);
  // Position, normal and color views of vertex array
  Cr::Containers::StridedArrayView1D<Mn::Vector3> positions =
      vertices.slice(&Vertex::position);
  Cr::Containers::StridedArrayView1D<Mn::Vector3> normals =
      vertices.slice(&Vertex::normal);
  Cr::Containers::StridedArrayView1D<Mn::Color3ub> colors =
      vertices.slice(&Vertex::color);

  // Beginning Endcap
  Mn::UnsignedInt circlePtIDX = 0;
  Mn::Vector3 tangent = trajectory[1] - trajectory[0];
  // get the orientation matrix assuming y-up preference
  Mn::Matrix4 tangentOrientation = Mn::Matrix4::lookAt(
      trajectory[0], trajectory[0] + tangent, Mn::Vector3{0, 1.0, 0});
  for (int i = 0; i < numSegments; ++i) {
    // build vertex (circleVerts[i] is at radius)
    positions[circlePtIDX] = tangentOrientation.transformPoint(circleVerts[i]);
    // pre-rotated normal for circle is normalized point
    normals[circlePtIDX] =
        tangentOrientation.transformVector(circleNormVerts[i]);
    colors[circlePtIDX] = convertInterpClrVecToUBClr(trajColors[0], clrSpace);
    ++circlePtIDX;
  }
  // add beginning cap vert at the end of the list
  // build vertex (circleVerts[i] is at radius)
  positions[vertexCount - 2] = trajectory[0];
  // normal points out at beginning cap vert
  normals[vertexCount - 2] =
      tangentOrientation.transformVector({0.0f, 0.0f, -1.0f});
  colors[vertexCount - 2] = convertInterpClrVecToUBClr(trajColors[0], clrSpace);

  for (Mn::UnsignedInt vertIx = 1; vertIx < trajSize - 1; ++vertIx) {
    const Mn::Vector3& vert = trajectory[vertIx];
    Mn::Vector3 pTangent = vert - trajectory[vertIx - 1];
    Mn::Vector3 nTangent = trajectory[vertIx + 1] - vert;
    tangent = (pTangent + nTangent) / 2.0;
    // get the orientation matrix assuming y-up preference
    tangentOrientation =
        Mn::Matrix4::lookAt(vert, vert + tangent, Mn::Vector3{0, 1.0, 0});
    for (int i = 0; i < numSegments; ++i) {
      // build vertex (circleVerts[i] is at radius)
      positions[circlePtIDX] =
          tangentOrientation.transformPoint(circleVerts[i]);
      // pre-rotated normal for circle is normalized point
      normals[circlePtIDX] =
          tangentOrientation.transformVector(circleNormVerts[i]);
      colors[circlePtIDX] =
          convertInterpClrVecToUBClr(trajColors[vertIx], clrSpace);
      ++circlePtIDX;
    }
  }

  // Ending Endcap
  int idx = trajSize - 1;
  tangent = trajectory[idx] - trajectory[idx - 1];
  // get the orientation matrix assuming y-up preference
  tangentOrientation = Mn::Matrix4::lookAt(
      trajectory[idx], trajectory[idx] + tangent, Mn::Vector3{0, 1.0, 0});
  for (int i = 0; i < numSegments; ++i) {
    // build vertex (circleVerts[i] is at radius)
    positions[circlePtIDX] = tangentOrientation.transformPoint(circleVerts[i]);
    // pre-rotated normal for circle is normalized point
    normals[circlePtIDX] =
        tangentOrientation.transformVector(circleNormVerts[i]);
    colors[circlePtIDX] = convertInterpClrVecToUBClr(trajColors[idx], clrSpace);
    ++circlePtIDX;
  }
  // add end cap vert
  // build vertex (circleVerts[i] is at radius)
  positions[vertexCount - 1] = trajectory[idx];
  // normal points out at end cap vert
  normals[vertexCount - 1] =
      tangentOrientation.transformVector({0.0f, 0.0f, 1.0f});
  colors[vertexCount - 1] =
      convertInterpClrVecToUBClr(trajColors[idx], clrSpace);

  // 4. Create polys between all points
  Cr::Containers::Array<char> indexData{
      Cr::NoInit, 6 * numSegments * trajSize * sizeof(Mn::UnsignedInt)};
  Cr::Containers::ArrayView<Mn::UnsignedInt> indices =
      Cr::Containers::arrayCast<Mn::UnsignedInt>(indexData);

  // create triangle indices for each tube pair correspondance - cw winding
  /*
            +n---+n+1
            | \ F2|
            |  \  |
            |F1 \ |
            +0---+1
        F1 = [+0, +n, +1]
        F2 = [+1, +n, +n+1]
   */
  int iListIDX = 0;
  for (Mn::UnsignedInt vIdx = 0; vIdx < trajSize - 1;
       ++vIdx) {  // skip last circle (adding forward)
    int vIdxNumSeg = vIdx * numSegments;
    for (Mn::UnsignedInt circleIx = 0; circleIx < numSegments; ++circleIx) {
      Mn::UnsignedInt ix = circleIx + vIdxNumSeg;  //+0
      Mn::UnsignedInt ixNext = ix + numSegments;   //+n
      Mn::UnsignedInt ixPlus = ix + 1;             //+1
      Mn::UnsignedInt ixNextPlus = ixNext + 1;     //+n+1
      if (circleIx == numSegments - 1) {
        // last vert in a circle wraps to relative 0
        ixPlus = vIdxNumSeg;
        ixNextPlus = vIdxNumSeg + numSegments;
      }
      // F1
      indices[iListIDX++] = ix;
      indices[iListIDX++] = ixNext;
      indices[iListIDX++] = ixPlus;
      // F2
      indices[iListIDX++] = ixPlus;
      indices[iListIDX++] = ixNext;
      indices[iListIDX++] = ixNextPlus;
    }
  }
  int offset = numSegments * (trajSize - 1);

  // end caps - verts added at the end of the vertices array
  for (Mn::UnsignedInt circleIx = 0; circleIx < numSegments; ++circleIx) {
    // first endcap
    Mn::UnsignedInt ix = circleIx;
    Mn::UnsignedInt ixPlus = (ix + 1) % numSegments;  //+1
    indices[iListIDX++] = (ix);
    indices[iListIDX++] = (ixPlus);
    indices[iListIDX++] = (vertexCount - 2);
    // last endcap
    ix += offset;
    ixPlus += offset;  //+1
    indices[iListIDX++] = (ixPlus);
    indices[iListIDX++] = (ix);
    indices[iListIDX++] = (vertexCount - 1);
  }

  // Finally, make the MeshData. The indices have to be constructed first
  // because function argument evaluation order is not guaranteed and so you
  // might end up with the move happening before the MeshIndexData construction,
  // which would result in 0 indices)

  // Building the mesh this way obviates the need for an interleaving step

  Mn::Trade::MeshData meshData{
      Mn::MeshPrimitive::Triangles,
      std::move(indexData),
      Mn::Trade::MeshIndexData{indices},
      std::move(vertexData),
      {Mn::Trade::MeshAttributeData{Mn::Trade::MeshAttribute::Position,
                                    positions},
       Mn::Trade::MeshAttributeData{Mn::Trade::MeshAttribute::Normal, normals},
       Mn::Trade::MeshAttributeData{Mn::Trade::MeshAttribute::Color, colors}},
      static_cast<Mn::UnsignedInt>(positions.size())};

  return meshData;
}  // ResourceManager::trajectoryTubeSolid