From c52cc2f402f2bb0aa01d7d87006e2494422ec258 Mon Sep 17 00:00:00 2001
From: =?UTF-8?q?D=C5=BEenan=20Zuki=C4=87?= <dzenan.zukic@kitware.com>
Date: Sat, 15 Apr 2017 11:59:30 -0400
Subject: [PATCH] COMP: using size_t more consistently and other warnings on
 MSVC/Windows

---
 .../imstkLinearProjectionConstraint.cpp       |  6 ++---
 .../imstkLinearProjectionConstraint.h         | 10 ++++----
 Base/Core/imstkColor.cpp                      |  2 +-
 Base/Core/imstkModule.cpp                     |  2 +-
 Base/Devices/imstkVRPNDeviceClient.cpp        |  2 +-
 Base/Devices/imstkVRPNDeviceServer.cpp        |  4 ++--
 Base/Devices/imstkVRPNDeviceServer.h          |  8 +++----
 .../ObjectModels/imstkPbdModel.cpp            |  4 ++--
 Base/Geometry/Map/imstkTetraTriangleMap.cpp   | 14 +++++------
 Base/Geometry/Map/imstkTetraTriangleMap.h     |  4 ++--
 Base/Geometry/Mesh/imstkHexahedralMesh.cpp    |  2 +-
 Base/Geometry/Mesh/imstkHexahedralMesh.h      |  2 +-
 Base/Geometry/Mesh/imstkMesh.cpp              |  9 ++++----
 Base/Geometry/Mesh/imstkMesh.h                |  4 ++--
 Base/Geometry/Mesh/imstkSurfaceMesh.cpp       | 16 ++++++-------
 Base/Geometry/Mesh/imstkSurfaceMesh.h         |  2 +-
 Base/Geometry/Mesh/imstkTetrahedralMesh.cpp   | 18 ++++++---------
 Base/Geometry/Mesh/imstkTetrahedralMesh.h     |  2 +-
 Base/Geometry/Reader/imstkMSHMeshIO.cpp       |  3 +++
 Base/Geometry/Reader/imstkVegaMeshIO.cpp      | 16 ++++++-------
 .../imstkVTKSurfaceMeshRenderDelegate.cpp     | 23 ++++++++++++-------
 CMakeLists.txt                                |  5 ++++
 22 files changed, 85 insertions(+), 73 deletions(-)

diff --git a/Base/Constraint/PbdConstraints/imstkLinearProjectionConstraint.cpp b/Base/Constraint/PbdConstraints/imstkLinearProjectionConstraint.cpp
index 617bfae0d..84a19ed66 100644
--- a/Base/Constraint/PbdConstraints/imstkLinearProjectionConstraint.cpp
+++ b/Base/Constraint/PbdConstraints/imstkLinearProjectionConstraint.cpp
@@ -25,7 +25,7 @@ namespace  imstk
 {
 
 LinearProjectionConstraint::
-LinearProjectionConstraint(const unsigned int& nodeId, const bool isFixed /*= false*/)
+LinearProjectionConstraint(const size_t& nodeId, const bool isFixed /*= false*/)
 {
     m_nodeId = nodeId;
     if (isFixed)
@@ -36,14 +36,14 @@ LinearProjectionConstraint(const unsigned int& nodeId, const bool isFixed /*= fa
 }
 
 void
-LinearProjectionConstraint::setProjection(const unsigned int& nodeId, const Vec3d& p, const Vec3d& q /*= Vec3d::Zero()*/)
+LinearProjectionConstraint::setProjection(const size_t& nodeId, const Vec3d& p, const Vec3d& q /*= Vec3d::Zero()*/)
 {
     m_nodeId = nodeId;
     m_projection = Mat3d::Identity() - p*p.transpose() - q*q.transpose();
 }
 
 void
-LinearProjectionConstraint::setProjectorToDirichlet(const unsigned int& nodeId)
+LinearProjectionConstraint::setProjectorToDirichlet(const size_t& nodeId)
 {
     m_nodeId = nodeId;
     m_projection = Mat3d::Zero();
diff --git a/Base/Constraint/PbdConstraints/imstkLinearProjectionConstraint.h b/Base/Constraint/PbdConstraints/imstkLinearProjectionConstraint.h
index da4bba63d..78f3f24a9 100644
--- a/Base/Constraint/PbdConstraints/imstkLinearProjectionConstraint.h
+++ b/Base/Constraint/PbdConstraints/imstkLinearProjectionConstraint.h
@@ -38,7 +38,7 @@ public:
     ///
     /// \brief Constructor
     ///
-    LinearProjectionConstraint(const unsigned int& nodeId, const bool isFixed = false);
+    LinearProjectionConstraint(const size_t& nodeId, const bool isFixed = false);
     LinearProjectionConstraint() = delete;
 
     ///
@@ -49,12 +49,12 @@ public:
     ///
     /// \brief Form the projection
     ///
-    void setProjection(const unsigned int& nodeId, const Vec3d& p, const Vec3d& q = Vec3d::Zero());
+    void setProjection(const size_t& nodeId, const Vec3d& p, const Vec3d& q = Vec3d::Zero());
 
     ///
     /// \brief Set the projector to simulate Dirichlet conditions
     ///
-    void setProjectorToDirichlet(const unsigned int& nodeId);
+    void setProjectorToDirichlet(const size_t& nodeId);
 
     ///
     /// \brief Reset the linear projector
@@ -88,13 +88,13 @@ public:
     ///
     /// \brief Get the node id
     ///
-    inline const unsigned int& getNodeId() const
+    inline const size_t& getNodeId() const
     {
         return m_nodeId;
     }
 
 private:
-    unsigned int m_nodeId;                  ///> Node id
+    size_t m_nodeId;                  ///> Node id
     bool m_isFixedConstraint = false;       ///> Flag to know if that node is fixed
     Mat3d m_projection = Mat3d::Identity(); ///> Orthogonal projector
     Vec3d m_value = Vec3d(0., 0., 0.);      ///> Value in the subspace: range(I-m_projector)
diff --git a/Base/Core/imstkColor.cpp b/Base/Core/imstkColor.cpp
index 76e941984..47b20a8b1 100644
--- a/Base/Core/imstkColor.cpp
+++ b/Base/Core/imstkColor.cpp
@@ -93,7 +93,7 @@ std::ostream& operator<<(std::ostream& os, const Color& c)
     os << "R = " << c.r << '\n'
        << "G = " << c.g << '\n'
        << "B = " << c.b << '\n'
-       << "\u03B1 = " << c.a ;
+       << "A = " << c.a ;
     return os;
 }
 
diff --git a/Base/Core/imstkModule.cpp b/Base/Core/imstkModule.cpp
index e93381fba..1709b9044 100644
--- a/Base/Core/imstkModule.cpp
+++ b/Base/Core/imstkModule.cpp
@@ -52,7 +52,7 @@ Module::start()
     // Keep active, wait for terminating call
     std::chrono::steady_clock::time_point previous_t = std::chrono::steady_clock::now() - std::chrono::minutes(1);
     std::chrono::steady_clock::time_point current_t;
-    int elapsed;
+    long long elapsed;
     while (m_status !=  ModuleStatus::TERMINATING)
     {
         if (m_status == ModuleStatus::PAUSING)
diff --git a/Base/Devices/imstkVRPNDeviceClient.cpp b/Base/Devices/imstkVRPNDeviceClient.cpp
index 10a23ec7f..2c65083c2 100644
--- a/Base/Devices/imstkVRPNDeviceClient.cpp
+++ b/Base/Devices/imstkVRPNDeviceClient.cpp
@@ -64,7 +64,7 @@ VRPNDeviceClient::runModule()
     }
     if (this->getForceEnabled())
     {
-        m_vrpnForceDevice->setFF_Force(m_force[0], m_force[1], m_force[2]);
+        m_vrpnForceDevice->setFF_Force(vrpn_float32(m_force[0]), vrpn_float32(m_force[1]), vrpn_float32(m_force[2]));
         m_vrpnForceDevice->sendForceField();
         m_vrpnForceDevice->mainloop();
     }
diff --git a/Base/Devices/imstkVRPNDeviceServer.cpp b/Base/Devices/imstkVRPNDeviceServer.cpp
index 45ad00e66..b39a67414 100644
--- a/Base/Devices/imstkVRPNDeviceServer.cpp
+++ b/Base/Devices/imstkVRPNDeviceServer.cpp
@@ -32,7 +32,7 @@ namespace imstk
 {
 
 void
-VRPNDeviceServer::addDevice(std::string deviceName, DeviceType deviceType, size_t id)
+VRPNDeviceServer::addDevice(std::string deviceName, DeviceType deviceType, int id)
 {
     m_deviceInfoMap[deviceName] = std::make_pair(deviceType,id);
 
@@ -56,7 +56,7 @@ VRPNDeviceServer::initModule()
     {
         std::string name = device.first;
         DeviceType type = device.second.first;
-        size_t id = device.second.second;
+        auto id = device.second.second;
 
         switch (type)
         {
diff --git a/Base/Devices/imstkVRPNDeviceServer.h b/Base/Devices/imstkVRPNDeviceServer.h
index a5ad992a8..36081925b 100644
--- a/Base/Devices/imstkVRPNDeviceServer.h
+++ b/Base/Devices/imstkVRPNDeviceServer.h
@@ -74,7 +74,7 @@ public:
     ///
     /// \brief Add device
     ///
-    void addDevice(std::string deviceName, DeviceType deviceType, size_t id = 0);
+    void addDevice(std::string deviceName, DeviceType deviceType, int id = 0);
 
 protected:
 
@@ -98,9 +98,9 @@ private:
     const std::string m_machine; ///< machine name or IP
     const int m_port;            ///< connection port
 
-    std::map<std::string, std::pair<DeviceType, size_t>> m_deviceInfoMap;///< list of iMSTK client info
-    vrpn_Connection * m_serverConnection;                                ///< VRPN server connection
-    vrpn_MainloopContainer* m_deviceConnections;                         ///< VRPN device connections
+    std::map<std::string, std::pair<DeviceType, int>> m_deviceInfoMap;///< list of iMSTK client info
+    vrpn_Connection * m_serverConnection;                             ///< VRPN server connection
+    vrpn_MainloopContainer* m_deviceConnections;                      ///< VRPN device connections
 
 };
 
diff --git a/Base/DynamicalModels/ObjectModels/imstkPbdModel.cpp b/Base/DynamicalModels/ObjectModels/imstkPbdModel.cpp
index 1c22be223..39fdf4696 100644
--- a/Base/DynamicalModels/ObjectModels/imstkPbdModel.cpp
+++ b/Base/DynamicalModels/ObjectModels/imstkPbdModel.cpp
@@ -316,8 +316,8 @@ PbdModel::initializeDihedralConstraints(const double& stiffness)
         std::sort(r2.begin(), r2.end());
         std::sort(r3.begin(), r3.end());
 
-        std::vector<unsigned int> rs;
-        std::vector<unsigned int>::iterator it;
+        std::vector<size_t> rs;
+        std::vector<size_t>::iterator it;
         // check if processed or not
         if (E[tri[0]][tri[1]] && E[tri[1]][tri[0]])
         {
diff --git a/Base/Geometry/Map/imstkTetraTriangleMap.cpp b/Base/Geometry/Map/imstkTetraTriangleMap.cpp
index ff664631e..6150cfb02 100644
--- a/Base/Geometry/Map/imstkTetraTriangleMap.cpp
+++ b/Base/Geometry/Map/imstkTetraTriangleMap.cpp
@@ -41,12 +41,12 @@ TetraTriangleMap::compute()
     for (const Vec3d& surfVertPos : triMesh->getVertexPositions())
     {
         // Find the enclosing or closest tetrahedron
-        int closestTetId = findEnclosingTetrahedron(tetMesh, surfVertPos);
-        if (closestTetId < 0)
+        size_t closestTetId = findEnclosingTetrahedron(tetMesh, surfVertPos);
+        if (closestTetId == std::numeric_limits<size_t>::max())
         {
             closestTetId = findClosestTetrahedron(tetMesh, surfVertPos);
         }
-        if (closestTetId < 0)
+        if (closestTetId == std::numeric_limits<size_t>::max())
         {
             LOG(WARNING) << "Could not find closest tetrahedron";
             return;
@@ -155,12 +155,12 @@ TetraTriangleMap::setSlave(std::shared_ptr<Geometry> slave)
     GeometryMap::setSlave(slave);
 }
 
-int
+size_t
 TetraTriangleMap::findClosestTetrahedron(std::shared_ptr<TetrahedralMesh> tetraMesh,
                                          const Vec3d& pos)
 {
     double closestDistance = MAX_D;
-    size_t closestTetrahedron = -1;
+    size_t closestTetrahedron = std::numeric_limits<size_t>::max();
     for (size_t tetId = 0; tetId < tetraMesh->getNumTetrahedra(); ++tetId)
     {
         Vec3d center(0, 0, 0);
@@ -180,7 +180,7 @@ TetraTriangleMap::findClosestTetrahedron(std::shared_ptr<TetrahedralMesh> tetraM
     return closestTetrahedron;
 }
 
-int
+size_t
 TetraTriangleMap::findEnclosingTetrahedron(std::shared_ptr<TetrahedralMesh> tetraMesh,
                                            const Vec3d& pos)
 {
@@ -202,7 +202,7 @@ TetraTriangleMap::findEnclosingTetrahedron(std::shared_ptr<TetrahedralMesh> tetr
     }
 
     // Check which probable tetrahedron the point belongs to
-    int enclosingTetrahedron = -1;
+    size_t enclosingTetrahedron = std::numeric_limits<size_t>::max();
     TetrahedralMesh::WeightsArray weights = {0.0, 0.0, 0.0, 0.0};
     for (const size_t& tetId : probablesTetId)
     {
diff --git a/Base/Geometry/Map/imstkTetraTriangleMap.h b/Base/Geometry/Map/imstkTetraTriangleMap.h
index 45ba33439..7b39e58d9 100644
--- a/Base/Geometry/Map/imstkTetraTriangleMap.h
+++ b/Base/Geometry/Map/imstkTetraTriangleMap.h
@@ -84,13 +84,13 @@ public:
     ///
     /// \brief Find the closest tetrahedron based on the distance to their centroids for a given point in 3D space
     ///
-    static int findClosestTetrahedron(std::shared_ptr<TetrahedralMesh> tetraMesh,
+    static size_t findClosestTetrahedron(std::shared_ptr<TetrahedralMesh> tetraMesh,
                                       const Vec3d& pos);
 
     ///
     /// \brief Find the tetrahedron that encloses a given point in 3D space
     ///
-    static int findEnclosingTetrahedron(std::shared_ptr<TetrahedralMesh> tetraMesh,
+    static size_t findEnclosingTetrahedron(std::shared_ptr<TetrahedralMesh> tetraMesh,
                                         const Vec3d& pos);
 
 protected:
diff --git a/Base/Geometry/Mesh/imstkHexahedralMesh.cpp b/Base/Geometry/Mesh/imstkHexahedralMesh.cpp
index 44fa5a145..039fb2dc2 100644
--- a/Base/Geometry/Mesh/imstkHexahedralMesh.cpp
+++ b/Base/Geometry/Mesh/imstkHexahedralMesh.cpp
@@ -142,7 +142,7 @@ HexahedralMesh::getHexahedronVertices(const int& hexaNum) const
     return m_hexahedraVertices.at(hexaNum);
 }
 
-int
+size_t
 HexahedralMesh::getNumHexahedra() const
 {
     return m_hexahedraVertices.size();
diff --git a/Base/Geometry/Mesh/imstkHexahedralMesh.h b/Base/Geometry/Mesh/imstkHexahedralMesh.h
index fb396d519..bf241c989 100644
--- a/Base/Geometry/Mesh/imstkHexahedralMesh.h
+++ b/Base/Geometry/Mesh/imstkHexahedralMesh.h
@@ -98,7 +98,7 @@ public:
     ///
     /// \brief Returns the number of hexahedra
     ///
-    int getNumHexahedra() const;
+    size_t getNumHexahedra() const;
 
 protected:
 
diff --git a/Base/Geometry/Mesh/imstkMesh.cpp b/Base/Geometry/Mesh/imstkMesh.cpp
index 2eee5ac12..ac578f73a 100644
--- a/Base/Geometry/Mesh/imstkMesh.cpp
+++ b/Base/Geometry/Mesh/imstkMesh.cpp
@@ -195,15 +195,16 @@ Mesh::setPointDataArray(const std::string& arrayName, const StdVectorOfVectorf&
     m_pointDataMap[arrayName] = arrayData;
 }
 
-const StdVectorOfVectorf&
+const StdVectorOfVectorf* const
 Mesh::getPointDataArray(const std::string& arrayName) const
 {
-    if (!m_pointDataMap.count(arrayName))
+    auto it = m_pointDataMap.find(arrayName);
+    if (it == m_pointDataMap.end())
     {
         LOG(WARNING) << "No array with such name holds any point data.";
-        return StdVectorOfVectorf();
+        return nullptr;
     }
-    return m_pointDataMap.at(arrayName);
+    return &(it->second);
 }
 
 const size_t
diff --git a/Base/Geometry/Mesh/imstkMesh.h b/Base/Geometry/Mesh/imstkMesh.h
index 8e3e15610..8d5a08910 100644
--- a/Base/Geometry/Mesh/imstkMesh.h
+++ b/Base/Geometry/Mesh/imstkMesh.h
@@ -139,9 +139,9 @@ public:
     void setPointDataArray(const std::string& arrayName, const StdVectorOfVectorf& arrayData);
 
     ///
-    /// \brief Get a specific data array
+    /// \brief Get a specific data array. If the array name cannot be found, nullptr is returned.
     ///
-    const StdVectorOfVectorf& getPointDataArray(const std::string& arrayName) const;
+    const StdVectorOfVectorf* const getPointDataArray(const std::string& arrayName) const;
 
     ///
     /// \brief Returns the number of total vertices in the mesh
diff --git a/Base/Geometry/Mesh/imstkSurfaceMesh.cpp b/Base/Geometry/Mesh/imstkSurfaceMesh.cpp
index e1a180de3..56b17fd1f 100644
--- a/Base/Geometry/Mesh/imstkSurfaceMesh.cpp
+++ b/Base/Geometry/Mesh/imstkSurfaceMesh.cpp
@@ -161,13 +161,13 @@ SurfaceMesh::computeVerticesNormals()
 void
 SurfaceMesh::optimizeForDataLocality()
 {
-    const int numVertices = this->getNumVertices();
-    const int numTriangles = this->getNumTriangles();
+    const size_t numVertices = this->getNumVertices();
+    const size_t numTriangles = this->getNumTriangles();
 
     // First find the list of triangles a given vertex is part of
-    std::vector<std::vector<int>> vertexNeighbors;
+    std::vector<std::vector<size_t>> vertexNeighbors;
     vertexNeighbors.resize(this->getNumVertices());
-    int triId = 0;
+    size_t triId = 0;
     for (const auto &tri : this->getTrianglesVertices())
     {
         vertexNeighbors[tri[0]].push_back(triId);
@@ -178,11 +178,11 @@ SurfaceMesh::optimizeForDataLocality()
     }
 
     std::vector<TriangleArray> optimizedConnectivity;
-    std::vector<int> optimallyOrderedNodes;
-    std::list<int> triUnderConsideration;
+    std::vector<size_t> optimallyOrderedNodes;
+    std::list<size_t> triUnderConsideration;
     std::vector<bool> isNodeAdded(numVertices, false);
     std::vector<bool> isTriangleAdded(numTriangles, false);
-    std::list<int> newlyAddedNodes;
+    std::list<size_t> newlyAddedNodes;
 
     // A. Initialize
     optimallyOrderedNodes.push_back(0);
@@ -324,7 +324,7 @@ SurfaceMesh::getVertexBitangents() const
     return m_vertexBitangents;
 }
 
-int
+size_t
 SurfaceMesh::getNumTriangles() const
 {
     return this->m_trianglesVertices.size();
diff --git a/Base/Geometry/Mesh/imstkSurfaceMesh.h b/Base/Geometry/Mesh/imstkSurfaceMesh.h
index 28ffaf994..aa6a17cef 100644
--- a/Base/Geometry/Mesh/imstkSurfaceMesh.h
+++ b/Base/Geometry/Mesh/imstkSurfaceMesh.h
@@ -144,7 +144,7 @@ public:
     ///
     /// \brief Returns the number of triangles
     ///
-    int getNumTriangles() const;
+    size_t getNumTriangles() const;
 
     ///
     /// \brief Set/Get the array defining the default material coordinates
diff --git a/Base/Geometry/Mesh/imstkTetrahedralMesh.cpp b/Base/Geometry/Mesh/imstkTetrahedralMesh.cpp
index 1034fe85a..313818186 100644
--- a/Base/Geometry/Mesh/imstkTetrahedralMesh.cpp
+++ b/Base/Geometry/Mesh/imstkTetrahedralMesh.cpp
@@ -135,15 +135,14 @@ TetrahedralMesh::extractSurfaceMesh(std::shared_ptr<SurfaceMesh> surfaceMesh)
             c = tetVertArray[facePattern[t][2]];
 
             // search in reverse
-            for (int i = surfaceTri.size() - 1; i >= 0; i--)
+            for (auto it=surfaceTri.rbegin(); it!=surfaceTri.rend(); ++it)
             {
-                const auto &triA = surfaceTri.at(i);
-                if (((triA[0] == a) && ((triA[1] == b && triA[2] == c) || (triA[1] == c && triA[2] == b))) ||
-                    ((triA[1] == a) && ((triA[0] == b && triA[2] == c) || (triA[0] == c && triA[2] == b))) ||
-                    ((triA[2] == a) && ((triA[1] == b && triA[0] == c) || (triA[1] == c && triA[0] == b))))
+                if ((((*it)[0] == a) && (((*it)[1] == b && (*it)[2] == c) || ((*it)[1] == c && (*it)[2] == b))) ||
+                    (((*it)[1] == a) && (((*it)[0] == b && (*it)[2] == c) || ((*it)[0] == c && (*it)[2] == b))) ||
+                    (((*it)[2] == a) && (((*it)[1] == b && (*it)[0] == c) || ((*it)[1] == c && (*it)[0] == b))))
                 {
                     unique = false;
-                    foundAt = i;
+                    foundAt = surfaceTri.size() - 1 - (it - surfaceTri.rbegin());
                     break;
                 }
             }
@@ -178,10 +177,7 @@ TetrahedralMesh::extractSurfaceMesh(std::shared_ptr<SurfaceMesh> surfaceMesh)
 
         if (normal.dot(centroid - this->getVertexPosition(tetRemainingVert.at(faceId))) > 0)
         {
-            // swap
-            int tmpIndex = surfaceTri[faceId][2];
-            surfaceTri[faceId][2] = surfaceTri[faceId][1];
-            surfaceTri[faceId][2] = tmpIndex;
+            std::swap(surfaceTri[faceId][2], surfaceTri[faceId][1]);
         }
     }
 
@@ -289,7 +285,7 @@ TetrahedralMesh::getTetrahedronVertices(const size_t& tetId) const
     return m_tetrahedraVertices.at(tetId);
 }
 
-int
+size_t
 TetrahedralMesh::getNumTetrahedra() const
 {
     return m_tetrahedraVertices.size();
diff --git a/Base/Geometry/Mesh/imstkTetrahedralMesh.h b/Base/Geometry/Mesh/imstkTetrahedralMesh.h
index e0174184c..7c007afdc 100644
--- a/Base/Geometry/Mesh/imstkTetrahedralMesh.h
+++ b/Base/Geometry/Mesh/imstkTetrahedralMesh.h
@@ -119,7 +119,7 @@ public:
     ///
     /// \brief Returns the number of tetrahedra
     ///
-    int getNumTetrahedra() const;
+    size_t getNumTetrahedra() const;
 
 protected:
     std::vector<TetraArray> m_tetrahedraVertices; ///< vertices of the tetrahedra
diff --git a/Base/Geometry/Reader/imstkMSHMeshIO.cpp b/Base/Geometry/Reader/imstkMSHMeshIO.cpp
index d25afe909..0892d0562 100644
--- a/Base/Geometry/Reader/imstkMSHMeshIO.cpp
+++ b/Base/Geometry/Reader/imstkMSHMeshIO.cpp
@@ -416,6 +416,9 @@ MSHMeshIO::numElemNodes(const ElemType & elType)
         case ElemType::tetrahedronThirdOrder:           return 20;
         case ElemType::tetrahedronFourthOrder:          return 35;
         case ElemType::tetrahedronFifthOrder:           return 56;
+        default:
+            LOG(WARNING) << "MSHMeshIO::numElemNodes: Unknown element type";
+            return 0;
     }
 }
 
diff --git a/Base/Geometry/Reader/imstkVegaMeshIO.cpp b/Base/Geometry/Reader/imstkVegaMeshIO.cpp
index 0c6733345..4532a657d 100644
--- a/Base/Geometry/Reader/imstkVegaMeshIO.cpp
+++ b/Base/Geometry/Reader/imstkVegaMeshIO.cpp
@@ -140,7 +140,7 @@ void
 VegaMeshIO::copyVertices(std::shared_ptr<vega::VolumetricMesh> vegaMesh,
                              StdVectorOfVec3d& vertices)
 {
-    for(size_t i = 0; i < vegaMesh->getNumVertices(); ++i)
+    for(int i = 0; i < vegaMesh->getNumVertices(); ++i)
     {
         auto pos = *vegaMesh->getVertex(i);
         vertices.emplace_back(pos[0], pos[1], pos[2]);
@@ -155,9 +155,9 @@ VegaMeshIO::copyCells(std::shared_ptr<vega::VolumetricMesh> vegaMesh,
     std::array<size_t,dim> cell;
     for(size_t cellId = 0; cellId < vegaMesh->getNumElements(); ++cellId)
     {
-        for (size_t i = 0; i < vegaMesh->getNumElementVertices(); ++i)
+        for (int i = 0; i < vegaMesh->getNumElementVertices(); ++i)
         {
-            cell[i] = vegaMesh->getVertexIndex(cellId,i);
+            cell[i] = vegaMesh->getVertexIndex(int(cellId),i);
         }
         cells.emplace_back(cell);
     }
@@ -189,13 +189,13 @@ VegaMeshIO::convertVolumetricMeshToVegaMesh(const std::shared_ptr<imstk::Volumet
         std::vector<int> elements;
         for (const auto & tet : tetArray)
         {
-            elements.emplace_back(tet[0]);
-            elements.emplace_back(tet[1]);
-            elements.emplace_back(tet[2]);
-            elements.emplace_back(tet[3]);
+            elements.emplace_back(int(tet[0]));
+            elements.emplace_back(int(tet[1]));
+            elements.emplace_back(int(tet[2]));
+            elements.emplace_back(int(tet[3]));
         }
 
-        std::shared_ptr<vega::VolumetricMesh> vegaMesh(new vega::TetMesh(imstkVolTetMesh->getNumVertices(), &vertices[0], imstkVolTetMesh->getNumTetrahedra(), &elements[0], E, nu, density));
+        std::shared_ptr<vega::VolumetricMesh> vegaMesh(new vega::TetMesh(int(imstkVolTetMesh->getNumVertices()), &vertices[0], int(imstkVolTetMesh->getNumTetrahedra()), &elements[0], E, nu, density));
         if (!vegaMesh)
         {
             LOG(WARNING) << "VegaMeshIO::convertVolumetricMeshToVegaMesh error: Failed to create vega mesh";
diff --git a/Base/Rendering/RenderDelegate/imstkVTKSurfaceMeshRenderDelegate.cpp b/Base/Rendering/RenderDelegate/imstkVTKSurfaceMeshRenderDelegate.cpp
index 2dc69671a..6be283723 100644
--- a/Base/Rendering/RenderDelegate/imstkVTKSurfaceMeshRenderDelegate.cpp
+++ b/Base/Rendering/RenderDelegate/imstkVTKSurfaceMeshRenderDelegate.cpp
@@ -90,17 +90,24 @@ VTKSurfaceMeshRenderDelegate::VTKSurfaceMeshRenderDelegate(std::shared_ptr<Surfa
     {
         // Convert texture coordinates
         auto tcoords = m_geometry->getPointDataArray(m_geometry->getDefaultTCoords());
-        auto vtkTCoords = vtkSmartPointer<vtkFloatArray>::New();
-        vtkTCoords->SetNumberOfComponents(2);
-        vtkTCoords->SetName(m_geometry->getDefaultTCoords().c_str());
-
-        for (auto const tcoord : tcoords)
+        if (tcoords == nullptr)
         {
-            double tuple[2] = { tcoord[0], tcoord[1] };
-            vtkTCoords->InsertNextTuple(tuple);
+            LOG(WARNING) << "No default texture coordinates array for geometry " << m_geometry;
         }
+        else
+        {
+            auto vtkTCoords = vtkSmartPointer<vtkFloatArray>::New();
+            vtkTCoords->SetNumberOfComponents(2);
+            vtkTCoords->SetName(m_geometry->getDefaultTCoords().c_str());
 
-        polydata->GetPointData()->SetTCoords(vtkTCoords);
+            for (auto const tcoord : *tcoords)
+            {
+                double tuple[2] = { tcoord[0], tcoord[1] };
+                vtkTCoords->InsertNextTuple(tuple);
+            }
+
+            polydata->GetPointData()->SetTCoords(vtkTCoords);
+        }
     }
 
     // Setup Mapper & Actor
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 86f106153..1c10d2627 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -62,6 +62,11 @@ set(CMAKE_CXX_STANDARD 11)
 set(CMAKE_CXX_STANDARD_REQUIRED ON)
 set(THREADS_PREFER_PTHREAD_FLAG ON)
 
+if(MSVC)
+  add_definitions(-D_CRT_SECURE_NO_WARNINGS)
+  add_definitions(-D_SCL_SECURE_NO_WARNINGS)
+endif()
+
 #-----------------------------------------------------------------------------
 # SUPERBUILD
 #-----------------------------------------------------------------------------
-- 
GitLab