diff --git a/CMakeLists.txt b/CMakeLists.txt index caf91744..4785c20f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -160,6 +160,7 @@ elseif (UNIX) endif () find_package(CUDA REQUIRED) +enable_language(CUDA) if(NOT CMAKE_CUDA_ARCHITECTURES) set(CMAKE_CUDA_ARCHITECTURES 86) endif() diff --git a/src/cupoch/geometry/down_sample.cu b/src/cupoch/geometry/down_sample.cu index 65874b66..cf6fa264 100644 --- a/src/cupoch/geometry/down_sample.cu +++ b/src/cupoch/geometry/down_sample.cu @@ -167,6 +167,16 @@ std::shared_ptr PointCloud::SelectByMask( return output; } +std::shared_ptr PointCloud::SelectByIndex( + const std::vector &indices, bool invert) const { + return SelectByIndex(utility::device_vector(indices), invert); +} + +std::shared_ptr PointCloud::SelectByMask( + const std::vector &mask, bool invert) const { + return SelectByMask(utility::device_vector(mask), invert); +} + std::shared_ptr PointCloud::VoxelDownSample( float voxel_size) const { auto output = std::make_shared(); diff --git a/src/cupoch/geometry/graph.cu b/src/cupoch/geometry/graph.cu index 1598f360..3aa36444 100644 --- a/src/cupoch/geometry/graph.cu +++ b/src/cupoch/geometry/graph.cu @@ -177,8 +177,9 @@ Graph::Graph(const Graph &other) is_directed_(other.is_directed_) {} template -thrust::host_vector Graph::GetEdgeIndexOffsets() const { - thrust::host_vector edge_index_offsets = edge_index_offsets_; +std::vector Graph::GetEdgeIndexOffsets() const { + std::vector edge_index_offsets; + copy_device_to_host(edge_index_offsets_, edge_index_offsets); return edge_index_offsets; } @@ -189,8 +190,9 @@ void Graph::SetEdgeIndexOffsets( } template -thrust::host_vector Graph::GetEdgeWeights() const { - thrust::host_vector edge_weights = edge_weights_; +std::vector Graph::GetEdgeWeights() const { + std::vector edge_weights; + copy_device_to_host(edge_weights_, edge_weights); return edge_weights; } diff --git a/src/cupoch/geometry/graph.h b/src/cupoch/geometry/graph.h index 0355b220..a83d1f61 100644 --- a/src/cupoch/geometry/graph.h +++ b/src/cupoch/geometry/graph.h @@ -55,10 +55,10 @@ class Graph : public LineSet { Graph(const Graph &other); ~Graph(); - thrust::host_vector GetEdgeIndexOffsets() const; + std::vector GetEdgeIndexOffsets() const; void SetEdgeIndexOffsets( const thrust::host_vector &edge_index_offsets); - thrust::host_vector GetEdgeWeights() const; + std::vector GetEdgeWeights() const; void SetEdgeWeights(const thrust::host_vector &edge_weights); bool HasWeights() const { diff --git a/src/cupoch/geometry/image.cu b/src/cupoch/geometry/image.cu index 7d4680a8..314bff4c 100644 --- a/src/cupoch/geometry/image.cu +++ b/src/cupoch/geometry/image.cu @@ -389,13 +389,19 @@ Eigen::Vector2f Image::GetCenter() const { return Eigen::Vector2f(width_ / 2, height_ / 2); } -thrust::host_vector Image::GetData() const { - thrust::host_vector data = data_; +std::vector Image::GetData() const { + std::vector data(data_.size()); + copy_device_to_host(data_, data); return data; } void Image::SetData(const thrust::host_vector &data) { data_ = data; } +void Image::SetData(const std::vector &data) { + data_.resize(data.size()); + copy_host_to_device(data, data_); +} + bool Image::TestImageBoundary(float u, float v, float inner_margin /* = 0.0 */) const { @@ -519,6 +525,13 @@ std::shared_ptr Image::FilterHorizontal( return output; } +std::shared_ptr Image::FilterHorizontal( + const std::vector &kernel) const { + utility::device_vector d_kernel(kernel.size()); + copy_host_to_device(kernel, d_kernel); + return FilterHorizontal(d_kernel); +} + std::shared_ptr Image::Filter(Image::FilterType type) const { auto output = std::make_shared(); if (num_of_channels_ != 1 || bytes_per_channel_ != 4) { diff --git a/src/cupoch/geometry/image.h b/src/cupoch/geometry/image.h index 3dc60685..f0df9e80 100644 --- a/src/cupoch/geometry/image.h +++ b/src/cupoch/geometry/image.h @@ -85,8 +85,9 @@ class Image : public GeometryBaseNoTrans2D { Eigen::Vector2f GetMaxBound() const override; Eigen::Vector2f GetCenter() const override; - thrust::host_vector GetData() const; + std::vector GetData() const; void SetData(const thrust::host_vector &data); + void SetData(const std::vector &data); /// \brief Test if coordinate `(u, v)` is located in the inner_marge of the /// image. @@ -171,6 +172,9 @@ class Image : public GeometryBaseNoTrans2D { std::shared_ptr FilterHorizontal( const utility::device_vector &kernel) const; + std::shared_ptr FilterHorizontal( + const std::vector &kernel) const; + std::shared_ptr BilateralFilter(int diameter, float sigma_color, float sigma_space) const; diff --git a/src/cupoch/geometry/laserscanbuffer.cu b/src/cupoch/geometry/laserscanbuffer.cu index 4706f5f9..1fed051f 100644 --- a/src/cupoch/geometry/laserscanbuffer.cu +++ b/src/cupoch/geometry/laserscanbuffer.cu @@ -137,8 +137,8 @@ LaserScanBuffer::LaserScanBuffer(const LaserScanBuffer& other) max_angle_(other.max_angle_), origins_(other.origins_) {} -thrust::host_vector LaserScanBuffer::GetRanges() const { - thrust::host_vector ranges; +std::vector LaserScanBuffer::GetRanges() const { + std::vector ranges; if (top_ == bottom_) { return ranges; } @@ -161,8 +161,8 @@ thrust::host_vector LaserScanBuffer::GetRanges() const { } } -thrust::host_vector LaserScanBuffer::GetIntensities() const { - thrust::host_vector intensities; +std::vector LaserScanBuffer::GetIntensities() const { + std::vector intensities; if (top_ == bottom_) { return intensities; } @@ -303,6 +303,11 @@ template LaserScanBuffer& LaserScanBuffer::AddRanges( const Eigen::Matrix4f& transformation, const thrust::host_vector& intensities); +template LaserScanBuffer& LaserScanBuffer::AddRanges( + const std::vector& ranges, + const Eigen::Matrix4f& transformation, + const std::vector& intensities); + class ContainerLikePtr { public: diff --git a/src/cupoch/geometry/laserscanbuffer.h b/src/cupoch/geometry/laserscanbuffer.h index ad86f265..317a9a6f 100644 --- a/src/cupoch/geometry/laserscanbuffer.h +++ b/src/cupoch/geometry/laserscanbuffer.h @@ -48,8 +48,8 @@ class LaserScanBuffer : public GeometryBase3D { ~LaserScanBuffer(); LaserScanBuffer(const LaserScanBuffer &other); - thrust::host_vector GetRanges() const; - thrust::host_vector GetIntensities() const; + std::vector GetRanges() const; + std::vector GetIntensities() const; LaserScanBuffer &Clear() override; bool IsEmpty() const override; diff --git a/src/cupoch/geometry/lineset.cu b/src/cupoch/geometry/lineset.cu index 30700d30..769431a9 100644 --- a/src/cupoch/geometry/lineset.cu +++ b/src/cupoch/geometry/lineset.cu @@ -68,6 +68,13 @@ LineSet::LineSet( points_(points), lines_(lines) {} +template +LineSet::LineSet(const std::vector> &points, + const std::vector &lines) + : GeometryBaseXD(Geometry::GeometryType::LineSet), + points_(points), + lines_(lines) {} + template LineSet::LineSet(const std::vector> &path) : GeometryBaseXD(Geometry::GeometryType::LineSet) { @@ -101,6 +108,13 @@ void LineSet::SetPoints( points_ = points; } +template +void LineSet::SetPoints( + const std::vector> &points) { + points_.resize(points.size()); + copy_host_to_device(points, points_); +} + template thrust::host_vector> LineSet::GetPoints() const { @@ -113,6 +127,12 @@ void LineSet::SetLines(const thrust::host_vector &lines) { lines_ = lines; } +template +void LineSet::SetLines(const std::vector &lines) { + lines_.resize(lines.size()); + copy_host_to_device(lines, lines_); +} + template thrust::host_vector LineSet::GetLines() const { thrust::host_vector lines = lines_; @@ -125,6 +145,12 @@ void LineSet::SetColors( colors_ = colors; } +template +void LineSet::SetColors(const std::vector &colors) { + colors_.resize(colors.size()); + copy_host_to_device(colors, colors_); +} + template thrust::host_vector LineSet::GetColors() const { thrust::host_vector colors = colors_; diff --git a/src/cupoch/geometry/lineset.h b/src/cupoch/geometry/lineset.h index db069ae0..2830dc30 100644 --- a/src/cupoch/geometry/lineset.h +++ b/src/cupoch/geometry/lineset.h @@ -58,18 +58,24 @@ class LineSet : public GeometryBaseXD { const utility::pinned_host_vector &lines); LineSet(const thrust::host_vector> &points, const thrust::host_vector &lines); + LineSet(const std::vector> &points, + const std::vector &lines); LineSet(const std::vector> &path); LineSet(const LineSet &other); ~LineSet(); void SetPoints( const thrust::host_vector> &points); + void SetPoints( + const std::vector> &points); thrust::host_vector> GetPoints() const; void SetLines(const thrust::host_vector &lines); + void SetLines(const std::vector &lines); thrust::host_vector GetLines() const; void SetColors(const thrust::host_vector &colors); + void SetColors(const std::vector &colors); thrust::host_vector GetColors() const; public: diff --git a/src/cupoch/geometry/meshbase.cu b/src/cupoch/geometry/meshbase.cu index a7486b31..1ebf08fd 100644 --- a/src/cupoch/geometry/meshbase.cu +++ b/src/cupoch/geometry/meshbase.cu @@ -41,8 +41,9 @@ MeshBase &MeshBase::operator=(const MeshBase &other) { return *this; } -thrust::host_vector MeshBase::GetVertices() const { - thrust::host_vector vertices = vertices_; +std::vector MeshBase::GetVertices() const { + std::vector vertices(vertices_.size()); + copy_device_to_host(vertices_, vertices); return vertices; } @@ -51,8 +52,14 @@ void MeshBase::SetVertices( vertices_ = vertices; } -thrust::host_vector MeshBase::GetVertexNormals() const { - thrust::host_vector vertex_normals = vertex_normals_; +void MeshBase::SetVertices(const std::vector &vertices) { + vertices_.resize(vertices.size()); + copy_host_to_device(vertices, vertices_); +} + +std::vector MeshBase::GetVertexNormals() const { + std::vector vertex_normals(vertex_normals_.size()); + copy_device_to_host(vertex_normals_, vertex_normals); return vertex_normals; } @@ -61,8 +68,14 @@ void MeshBase::SetVertexNormals( vertex_normals_ = vertex_normals; } -thrust::host_vector MeshBase::GetVertexColors() const { - thrust::host_vector vertex_colors = vertex_colors_; +void MeshBase::SetVertexNormals(const std::vector &vertex_normals) { + vertex_normals_.resize(vertex_normals.size()); + copy_host_to_device(vertex_normals, vertex_normals_); +} + +std::vector MeshBase::GetVertexColors() const { + std::vector vertex_colors(vertex_colors_.size()); + copy_device_to_host(vertex_colors_, vertex_colors); return vertex_colors; } @@ -71,6 +84,11 @@ void MeshBase::SetVertexColors( vertex_colors_ = vertex_colors; } +void MeshBase::SetVertexColors(const std::vector &vertex_colors) { + vertex_colors_.resize(vertex_colors.size()); + copy_host_to_device(vertex_colors, vertex_colors_); +} + MeshBase &MeshBase::Clear() { vertices_.clear(); vertex_normals_.clear(); diff --git a/src/cupoch/geometry/meshbase.h b/src/cupoch/geometry/meshbase.h index 78a94cfe..d06d5478 100644 --- a/src/cupoch/geometry/meshbase.h +++ b/src/cupoch/geometry/meshbase.h @@ -59,17 +59,19 @@ class MeshBase : public GeometryBase3D { MeshBase(const MeshBase &other); MeshBase &operator=(const MeshBase &other); - thrust::host_vector GetVertices() const; + std::vector GetVertices() const; void SetVertices(const thrust::host_vector &vertices); + void SetVertices(const std::vector &vertices); - thrust::host_vector GetVertexNormals() const; + std::vector GetVertexNormals() const; void SetVertexNormals( const thrust::host_vector &vertex_normals); + void SetVertexNormals(const std::vector &vertex_normals); - thrust::host_vector GetVertexColors() const; + std::vector GetVertexColors() const; void SetVertexColors( const thrust::host_vector &vertex_colors); - + void SetVertexColors(const std::vector &vertex_colors); public: virtual MeshBase &Clear() override; virtual bool IsEmpty() const override; diff --git a/src/cupoch/geometry/occupancygrid.cu b/src/cupoch/geometry/occupancygrid.cu index de19ee95..5bd265c1 100644 --- a/src/cupoch/geometry/occupancygrid.cu +++ b/src/cupoch/geometry/occupancygrid.cu @@ -537,6 +537,14 @@ OccupancyGrid& OccupancyGrid::Insert( return Insert(dev_points, viewpoint, max_range); } +OccupancyGrid& OccupancyGrid::Insert(const std::vector& points, + const Eigen::Vector3f& viewpoint, + float max_range) { + utility::device_vector dev_points(points.size()); + copy_host_to_device(points, dev_points); + return Insert(dev_points, viewpoint, max_range); +} + OccupancyGrid& OccupancyGrid::Insert(const geometry::PointCloud& pointcloud, const Eigen::Vector3f& viewpoint, float max_range) { diff --git a/src/cupoch/geometry/occupancygrid.h b/src/cupoch/geometry/occupancygrid.h index 303e8776..40b3caa0 100644 --- a/src/cupoch/geometry/occupancygrid.h +++ b/src/cupoch/geometry/occupancygrid.h @@ -112,6 +112,9 @@ class OccupancyGrid : public DenseGrid { const thrust::host_vector& points, const Eigen::Vector3f& viewpoint, float max_range = -1.0); + OccupancyGrid& Insert(const std::vector& points, + const Eigen::Vector3f& viewpoint, + float max_range = -1.0); OccupancyGrid& Insert(const PointCloud& pointcloud, const Eigen::Vector3f& viewpoint, float max_range = -1.0); diff --git a/src/cupoch/geometry/pointcloud.cu b/src/cupoch/geometry/pointcloud.cu index cab90e24..1635af2f 100644 --- a/src/cupoch/geometry/pointcloud.cu +++ b/src/cupoch/geometry/pointcloud.cu @@ -168,8 +168,14 @@ void PointCloud::SetPoints(const thrust::host_vector &points) { points_ = points; } -thrust::host_vector PointCloud::GetPoints() const { - thrust::host_vector points = points_; +void PointCloud::SetPoints(const std::vector &points) { + points_.resize(points.size()); + copy_host_to_device(points, points_); +} + +std::vector PointCloud::GetPoints() const { + std::vector points(points_.size()); + copy_device_to_host(points_, points); return points; } @@ -178,8 +184,14 @@ void PointCloud::SetNormals( normals_ = normals; } -thrust::host_vector PointCloud::GetNormals() const { - thrust::host_vector normals = normals_; +void PointCloud::SetNormals(const std::vector &normals) { + normals_.resize(normals.size()); + copy_host_to_device(normals, normals_); +} + +std::vector PointCloud::GetNormals() const { + std::vector normals(normals_.size()); + copy_device_to_host(normals_, normals); return normals; } @@ -187,8 +199,14 @@ void PointCloud::SetColors(const thrust::host_vector &colors) { colors_ = colors; } -thrust::host_vector PointCloud::GetColors() const { - thrust::host_vector colors = colors_; +void PointCloud::SetColors(const std::vector &colors) { + colors_.resize(colors.size()); + copy_host_to_device(colors, colors_); +} + +std::vector PointCloud::GetColors() const { + std::vector colors(colors_.size()); + copy_device_to_host(colors_, colors); return colors; } diff --git a/src/cupoch/geometry/pointcloud.h b/src/cupoch/geometry/pointcloud.h index 54781926..4ef74926 100644 --- a/src/cupoch/geometry/pointcloud.h +++ b/src/cupoch/geometry/pointcloud.h @@ -51,13 +51,16 @@ class PointCloud : public GeometryBase3D { PointCloud &operator=(const PointCloud &other); void SetPoints(const thrust::host_vector &points); - thrust::host_vector GetPoints() const; + void SetPoints(const std::vector &points); + std::vector GetPoints() const; void SetNormals(const thrust::host_vector &normals); - thrust::host_vector GetNormals() const; + void SetNormals(const std::vector &normals); + std::vector GetNormals() const; void SetColors(const thrust::host_vector &colors); - thrust::host_vector GetColors() const; + void SetColors(const std::vector &colors); + std::vector GetColors() const; PointCloud &Clear() override; bool IsEmpty() const override; @@ -124,6 +127,14 @@ class PointCloud : public GeometryBase3D { const utility::device_vector &mask, bool invert = false) const; + std::shared_ptr SelectByIndex( + const std::vector &indices, + bool invert = false) const; + + std::shared_ptr SelectByMask( + const std::vector &mask, + bool invert = false) const; + /// Function to downsample \param input pointcloud into output pointcloud /// with a voxel \param voxel_size defines the resolution of the voxel grid, /// smaller value leads to denser output point cloud. Normals and colors are diff --git a/src/cupoch/geometry/trianglemesh.cu b/src/cupoch/geometry/trianglemesh.cu index 27ea7e9a..4ffd80af 100644 --- a/src/cupoch/geometry/trianglemesh.cu +++ b/src/cupoch/geometry/trianglemesh.cu @@ -346,8 +346,9 @@ TriangleMesh &TriangleMesh::operator=(const TriangleMesh &other) { return *this; } -thrust::host_vector TriangleMesh::GetTriangles() const { - thrust::host_vector triangles = triangles_; +std::vector TriangleMesh::GetTriangles() const { + std::vector triangles(triangles_.size()); + copy_device_to_host(triangles_, triangles); return triangles; } @@ -356,8 +357,14 @@ void TriangleMesh::SetTriangles( triangles_ = triangles; } -thrust::host_vector TriangleMesh::GetTriangleNormals() const { - thrust::host_vector triangle_normals = triangle_normals_; +void TriangleMesh::SetTriangles(const std::vector &triangles) { + triangles_.resize(triangles.size()); + copy_host_to_device(triangles, triangles_); +} + +std::vector TriangleMesh::GetTriangleNormals() const { + std::vector triangle_normals(triangle_normals_.size()); + copy_device_to_host(triangle_normals_, triangle_normals); return triangle_normals; } @@ -366,8 +373,14 @@ void TriangleMesh::SetTriangleNormals( triangle_normals_ = triangle_normals; } -thrust::host_vector TriangleMesh::GetEdgeList() const { - thrust::host_vector edge_list = edge_list_; +void TriangleMesh::SetTriangleNormals(const std::vector &triangle_normals) { + triangle_normals_.resize(triangle_normals.size()); + copy_host_to_device(triangle_normals, triangle_normals_); +} + +std::vector TriangleMesh::GetEdgeList() const { + std::vector edge_list(edge_list_.size()); + copy_device_to_host(edge_list_, edge_list); return edge_list; } @@ -376,16 +389,27 @@ void TriangleMesh::SetEdgeList( edge_list_ = edge_list; } -thrust::host_vector TriangleMesh::GetTriangleUVs() const { - thrust::host_vector triangle_uvs = triangle_uvs_; +void TriangleMesh::SetEdgeList(const std::vector &edge_list) { + edge_list_.resize(edge_list.size()); + copy_host_to_device(edge_list, edge_list_); +} + +std::vector TriangleMesh::GetTriangleUVs() const { + std::vector triangle_uvs(triangle_uvs_.size()); + copy_device_to_host(triangle_uvs_, triangle_uvs); return triangle_uvs; } void TriangleMesh::SetTriangleUVs( - thrust::host_vector &triangle_uvs) { + const thrust::host_vector &triangle_uvs) { triangle_uvs_ = triangle_uvs; } +void TriangleMesh::SetTriangleUVs(const std::vector &triangle_uvs) { + triangle_uvs_.resize(triangle_uvs.size()); + copy_host_to_device(triangle_uvs, triangle_uvs_); +} + TriangleMesh &TriangleMesh::Clear() { MeshBase::Clear(); triangles_.clear(); diff --git a/src/cupoch/geometry/trianglemesh.h b/src/cupoch/geometry/trianglemesh.h index d0bf7a68..b9cd24a0 100644 --- a/src/cupoch/geometry/trianglemesh.h +++ b/src/cupoch/geometry/trianglemesh.h @@ -40,18 +40,22 @@ class TriangleMesh : public MeshBase { ~TriangleMesh() override; TriangleMesh &operator=(const TriangleMesh &other); - thrust::host_vector GetTriangles() const; + std::vector GetTriangles() const; void SetTriangles(const thrust::host_vector &triangles); + void SetTriangles(const std::vector &triangles); - thrust::host_vector GetTriangleNormals() const; + std::vector GetTriangleNormals() const; void SetTriangleNormals( const thrust::host_vector &triangle_normals); + void SetTriangleNormals(const std::vector &triangle_normals); - thrust::host_vector GetEdgeList() const; + std::vector GetEdgeList() const; void SetEdgeList(const thrust::host_vector &edge_list); + void SetEdgeList(const std::vector &edge_list); - thrust::host_vector GetTriangleUVs() const; - void SetTriangleUVs(thrust::host_vector &triangle_uvs); + std::vector GetTriangleUVs() const; + void SetTriangleUVs(const thrust::host_vector &triangle_uvs); + void SetTriangleUVs(const std::vector &triangle_uvs); public: virtual TriangleMesh &Clear() override; diff --git a/src/cupoch/geometry/voxelgrid.cu b/src/cupoch/geometry/voxelgrid.cu index 5d13ed2e..289a3eec 100644 --- a/src/cupoch/geometry/voxelgrid.cu +++ b/src/cupoch/geometry/voxelgrid.cu @@ -148,6 +148,14 @@ void VoxelGrid::SetVoxels( voxels_values_ = voxels_values; } +void VoxelGrid::SetVoxels(const std::vector &voxels_keys, + const std::vector &voxels_values) { + voxels_keys_.resize(voxels_keys.size()); + voxels_values_.resize(voxels_values.size()); + copy_host_to_device(voxels_keys, voxels_keys_); + copy_host_to_device(voxels_values, voxels_values_); +} + VoxelGrid &VoxelGrid::Clear() { voxel_size_ = 0.0; origin_ = Eigen::Vector3f::Zero(); diff --git a/src/cupoch/geometry/voxelgrid.h b/src/cupoch/geometry/voxelgrid.h index 5974dad5..1c8b03fc 100644 --- a/src/cupoch/geometry/voxelgrid.h +++ b/src/cupoch/geometry/voxelgrid.h @@ -91,6 +91,8 @@ class VoxelGrid : public GeometryBase3D { GetVoxels() const; void SetVoxels(const thrust::host_vector &voxels_keys, const thrust::host_vector &voxels_values); + void SetVoxels(const std::vector &voxels_keys, + const std::vector &voxels_values); VoxelGrid &Clear() override; bool IsEmpty() const override; diff --git a/src/cupoch/io/class_io/image_io.cu b/src/cupoch/io/class_io/image_io.cu index c2db31f4..d4e9b6eb 100644 --- a/src/cupoch/io/class_io/image_io.cu +++ b/src/cupoch/io/class_io/image_io.cu @@ -30,13 +30,13 @@ void HostImage::FromDevice(const geometry::Image& image) { data_.resize(image.data_.size()); Prepare(image.width_, image.height_, image.num_of_channels_, image.bytes_per_channel_); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(data_.data()), thrust::raw_pointer_cast(image.data_.data()), image.data_.size(), cudaMemcpyDeviceToHost)); + copy_device_to_host(image.data_, data_); } void HostImage::ToDevice(geometry::Image& image) const { image.Prepare(width_, height_, num_of_channels_, bytes_per_channel_); image.data_.resize(data_.size()); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(image.data_.data()), thrust::raw_pointer_cast(data_.data()), image.data_.size(), cudaMemcpyHostToDevice)); + copy_host_to_device(data_, image.data_); } void HostImage::Clear() { diff --git a/src/cupoch/io/class_io/pointcloud_io.cu b/src/cupoch/io/class_io/pointcloud_io.cu index 7f5a8280..3436b6cb 100644 --- a/src/cupoch/io/class_io/pointcloud_io.cu +++ b/src/cupoch/io/class_io/pointcloud_io.cu @@ -30,24 +30,18 @@ void HostPointCloud::FromDevice(const geometry::PointCloud& pointcloud) { points_.resize(pointcloud.points_.size()); normals_.resize(pointcloud.normals_.size()); colors_.resize(pointcloud.colors_.size()); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(points_.data()), thrust::raw_pointer_cast(pointcloud.points_.data()), - points_.size() * sizeof(Eigen::Vector3f), cudaMemcpyDeviceToHost)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(normals_.data()), thrust::raw_pointer_cast(pointcloud.normals_.data()), - normals_.size() * sizeof(Eigen::Vector3f), cudaMemcpyDeviceToHost)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(colors_.data()), thrust::raw_pointer_cast(pointcloud.colors_.data()), - colors_.size() * sizeof(Eigen::Vector3f), cudaMemcpyDeviceToHost)); + copy_device_to_host(pointcloud.points_, points_); + copy_device_to_host(pointcloud.normals_, normals_); + copy_device_to_host(pointcloud.colors_, colors_); } void HostPointCloud::ToDevice(geometry::PointCloud& pointcloud) const { pointcloud.points_.resize(points_.size()); pointcloud.normals_.resize(normals_.size()); pointcloud.colors_.resize(colors_.size()); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(pointcloud.points_.data()), thrust::raw_pointer_cast(points_.data()), - points_.size() * sizeof(Eigen::Vector3f), cudaMemcpyHostToDevice)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(pointcloud.normals_.data()), thrust::raw_pointer_cast(normals_.data()), - normals_.size() * sizeof(Eigen::Vector3f), cudaMemcpyHostToDevice)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(pointcloud.colors_.data()), thrust::raw_pointer_cast(colors_.data()), - colors_.size() * sizeof(Eigen::Vector3f), cudaMemcpyHostToDevice)); + copy_host_to_device(points_, pointcloud.points_); + copy_host_to_device(normals_, pointcloud.normals_); + copy_host_to_device(colors_, pointcloud.colors_); } void HostPointCloud::Clear() { diff --git a/src/cupoch/io/class_io/trianglemesh_io.cu b/src/cupoch/io/class_io/trianglemesh_io.cu index 6d9d46c7..31a29012 100644 --- a/src/cupoch/io/class_io/trianglemesh_io.cu +++ b/src/cupoch/io/class_io/trianglemesh_io.cu @@ -32,18 +32,12 @@ void HostTriangleMesh::FromDevice(const geometry::TriangleMesh& trianglemesh) { triangles_.resize(trianglemesh.triangles_.size()); triangle_normals_.resize(trianglemesh.triangle_normals_.size()); triangle_uvs_.resize(trianglemesh.triangle_uvs_.size()); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(vertices_.data()), thrust::raw_pointer_cast(trianglemesh.vertices_.data()), - vertices_.size() * sizeof(Eigen::Vector3f), cudaMemcpyDeviceToHost)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(vertex_normals_.data()), thrust::raw_pointer_cast(trianglemesh.vertex_normals_.data()), - vertex_normals_.size() * sizeof(Eigen::Vector3f), cudaMemcpyDeviceToHost)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(vertex_colors_.data()), thrust::raw_pointer_cast(trianglemesh.vertex_colors_.data()), - vertex_colors_.size() * sizeof(Eigen::Vector3f), cudaMemcpyDeviceToHost)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(triangles_.data()), thrust::raw_pointer_cast(trianglemesh.triangles_.data()), - triangles_.size() * sizeof(Eigen::Vector3i), cudaMemcpyDeviceToHost)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(triangle_normals_.data()), thrust::raw_pointer_cast(trianglemesh.triangle_normals_.data()), - triangle_normals_.size() * sizeof(Eigen::Vector3f), cudaMemcpyDeviceToHost)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(triangle_uvs_.data()), thrust::raw_pointer_cast(trianglemesh.triangle_uvs_.data()), - triangle_uvs_.size() * sizeof(Eigen::Vector2f), cudaMemcpyDeviceToHost)); + copy_device_to_host(trianglemesh.vertices_, vertices_); + copy_device_to_host(trianglemesh.vertex_normals_, vertex_normals_); + copy_device_to_host(trianglemesh.vertex_colors_, vertex_colors_); + copy_device_to_host(trianglemesh.triangles_, triangles_); + copy_device_to_host(trianglemesh.triangle_normals_, triangle_normals_); + copy_device_to_host(trianglemesh.triangle_uvs_, triangle_uvs_); texture_.FromDevice(trianglemesh.texture_); } @@ -54,18 +48,12 @@ void HostTriangleMesh::ToDevice(geometry::TriangleMesh& trianglemesh) const { trianglemesh.triangles_.resize(triangles_.size()); trianglemesh.triangle_normals_.resize(triangle_normals_.size()); trianglemesh.triangle_uvs_.resize(triangle_uvs_.size()); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(trianglemesh.vertices_.data()), thrust::raw_pointer_cast(vertices_.data()), - vertices_.size() * sizeof(Eigen::Vector3f), cudaMemcpyHostToDevice)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(trianglemesh.vertex_normals_.data()), thrust::raw_pointer_cast(vertex_normals_.data()), - vertex_normals_.size() * sizeof(Eigen::Vector3f), cudaMemcpyHostToDevice)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(trianglemesh.vertex_colors_.data()), thrust::raw_pointer_cast(vertex_colors_.data()), - vertex_colors_.size() * sizeof(Eigen::Vector3f), cudaMemcpyHostToDevice)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(trianglemesh.triangles_.data()), thrust::raw_pointer_cast(triangles_.data()), - triangles_.size() * sizeof(Eigen::Vector3i), cudaMemcpyHostToDevice)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(trianglemesh.triangle_normals_.data()), thrust::raw_pointer_cast(triangle_normals_.data()), - triangle_normals_.size() * sizeof(Eigen::Vector3f), cudaMemcpyHostToDevice)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(trianglemesh.triangle_uvs_.data()), thrust::raw_pointer_cast(triangle_uvs_.data()), - triangle_uvs_.size() * sizeof(Eigen::Vector2f), cudaMemcpyHostToDevice)); + copy_host_to_device(vertices_, trianglemesh.vertices_); + copy_host_to_device(vertex_normals_, trianglemesh.vertex_normals_); + copy_host_to_device(vertex_colors_, trianglemesh.vertex_colors_); + copy_host_to_device(triangles_, trianglemesh.triangles_); + copy_host_to_device(triangle_normals_, trianglemesh.triangle_normals_); + copy_host_to_device(triangle_uvs_, trianglemesh.triangle_uvs_); texture_.ToDevice(trianglemesh.texture_); } diff --git a/src/cupoch/io/class_io/voxelgrid_io.cu b/src/cupoch/io/class_io/voxelgrid_io.cu index 72ff9711..77fe4acc 100644 --- a/src/cupoch/io/class_io/voxelgrid_io.cu +++ b/src/cupoch/io/class_io/voxelgrid_io.cu @@ -29,19 +29,15 @@ using namespace cupoch::io; void HostVoxelGrid::FromDevice(const geometry::VoxelGrid& voxelgrid) { voxels_keys_.resize(voxelgrid.voxels_keys_.size()); voxels_values_.resize(voxelgrid.voxels_values_.size()); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(voxels_keys_.data()), thrust::raw_pointer_cast(voxelgrid.voxels_keys_.data()), - voxels_keys_.size() * sizeof(Eigen::Vector3i), cudaMemcpyDeviceToHost)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(voxels_values_.data()), thrust::raw_pointer_cast(voxelgrid.voxels_values_.data()), - voxels_values_.size() * sizeof(geometry::Voxel), cudaMemcpyDeviceToHost)); + copy_device_to_host(voxelgrid.voxels_keys_, voxels_keys_); + copy_device_to_host(voxelgrid.voxels_values_, voxels_values_); } void HostVoxelGrid::ToDevice(geometry::VoxelGrid& voxelgrid) const { voxelgrid.voxels_keys_.resize(voxels_keys_.size()); voxelgrid.voxels_values_.resize(voxels_values_.size()); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(voxelgrid.voxels_keys_.data()), thrust::raw_pointer_cast(voxels_keys_.data()), - voxels_keys_.size() * sizeof(Eigen::Vector3i), cudaMemcpyHostToDevice)); - cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(voxelgrid.voxels_values_.data()), thrust::raw_pointer_cast(voxels_values_.data()), - voxels_values_.size() * sizeof(geometry::Voxel), cudaMemcpyHostToDevice)); + copy_host_to_device(voxels_keys_, voxelgrid.voxels_keys_); + copy_host_to_device(voxels_values_, voxelgrid.voxels_values_); } void HostVoxelGrid::Clear() { diff --git a/src/cupoch/knn/kdtree_flann.cu b/src/cupoch/knn/kdtree_flann.cu index d7528cc0..f29607fd 100644 --- a/src/cupoch/knn/kdtree_flann.cu +++ b/src/cupoch/knn/kdtree_flann.cu @@ -128,6 +128,55 @@ int KDTreeFlann::SearchRadius(const T &query, return result; } +template +int KDTreeFlann::Search(const T &query, + const KDTreeSearchParam ¶m, + std::vector &indices, + std::vector &distance2) const { + utility::device_vector query_dv(1, query); + utility::device_vector indices_dv; + utility::device_vector distance2_dv; + auto result = Search(query_dv, param, indices_dv, distance2_dv); + indices.resize(indices_dv.size()); + distance2.resize(distance2_dv.size()); + copy_device_to_host(indices_dv, indices); + copy_device_to_host(distance2_dv, distance2); + return result; +} + +template +int KDTreeFlann::SearchKNN(const T &query, + int knn, + std::vector &indices, + std::vector &distance2) const { + utility::device_vector query_dv(1, query); + utility::device_vector indices_dv; + utility::device_vector distance2_dv; + auto result = SearchKNN(query_dv, knn, indices_dv, distance2_dv); + indices.resize(indices_dv.size()); + distance2.resize(distance2_dv.size()); + copy_device_to_host(indices_dv, indices); + copy_device_to_host(distance2_dv, distance2); + return result; +} + +template +int KDTreeFlann::SearchRadius(const T &query, + float radius, + int max_nn, + std::vector &indices, + std::vector &distance2) const { + utility::device_vector query_dv(1, query); + utility::device_vector indices_dv; + utility::device_vector distance2_dv; + auto result = SearchRadius(query_dv, radius, max_nn, indices_dv, distance2_dv); + indices.resize(indices_dv.size()); + distance2.resize(distance2_dv.size()); + copy_device_to_host(indices_dv, indices); + copy_device_to_host(distance2_dv, distance2); + return result; +} + template int KDTreeFlann::Search( const utility::device_vector &query, const KDTreeSearchParam ¶m, @@ -160,6 +209,22 @@ template int KDTreeFlann::SearchRadius( int max_nn, thrust::host_vector &indices, thrust::host_vector &distance2) const; +template int KDTreeFlann::Search( + const Eigen::Vector3f &query, + const KDTreeSearchParam ¶m, + std::vector &indices, + std::vector &distance2) const; +template int KDTreeFlann::SearchKNN( + const Eigen::Vector3f &query, + int knn, + std::vector &indices, + std::vector &distance2) const; +template int KDTreeFlann::SearchRadius( + const Eigen::Vector3f &query, + float radius, + int max_nn, + std::vector &indices, + std::vector &distance2) const; template bool KDTreeFlann::SetRawData( const utility::device_vector &data); @@ -195,6 +260,22 @@ template int KDTreeFlann::SearchRadius( int max_nn, thrust::host_vector &indices, thrust::host_vector &distance2) const; +template int KDTreeFlann::Search( + const Eigen::Vector2f &query, + const KDTreeSearchParam ¶m, + std::vector &indices, + std::vector &distance2) const; +template int KDTreeFlann::SearchKNN( + const Eigen::Vector2f &query, + int knn, + std::vector &indices, + std::vector &distance2) const; +template int KDTreeFlann::SearchRadius( + const Eigen::Vector2f &query, + float radius, + int max_nn, + std::vector &indices, + std::vector &distance2) const; template bool KDTreeFlann::SetRawData( const utility::device_vector &data); diff --git a/src/cupoch/knn/kdtree_flann.h b/src/cupoch/knn/kdtree_flann.h index a0aee1d3..b21fcfc9 100644 --- a/src/cupoch/knn/kdtree_flann.h +++ b/src/cupoch/knn/kdtree_flann.h @@ -109,6 +109,25 @@ class KDTreeFlann { thrust::host_vector &indices, thrust::host_vector &distance2) const; + template + int Search(const T &query, + const KDTreeSearchParam ¶m, + std::vector &indices, + std::vector &distance2) const; + + template + int SearchKNN(const T &query, + int knn, + std::vector &indices, + std::vector &distance2) const; + + template + int SearchRadius(const T &query, + float radius, + int max_nn, + std::vector &indices, + std::vector &distance2) const; + template bool SetRawData(InputIterator first, InputIterator last); diff --git a/src/cupoch/knn/lbvh_knn.cu b/src/cupoch/knn/lbvh_knn.cu index 4414bbbe..f1e2e35a 100644 --- a/src/cupoch/knn/lbvh_knn.cu +++ b/src/cupoch/knn/lbvh_knn.cu @@ -114,6 +114,22 @@ int LinearBoundingVolumeHierarchyKNN::SearchNN(const T &query, return result; } +template +int LinearBoundingVolumeHierarchyKNN::SearchNN(const T &query, + float radius, + std::vector &indices, + std::vector &distance2) const { + utility::device_vector query_dv(1, query); + utility::device_vector indices_dv; + utility::device_vector distance2_dv; + auto result = SearchNN(query_dv, radius, indices_dv, distance2_dv); + indices.resize(indices_dv.size()); + distance2.resize(distance2_dv.size()); + copy_device_to_host(indices_dv, indices); + copy_device_to_host(distance2_dv, distance2); + return result; +} + template bool LinearBoundingVolumeHierarchyKNN::SetRawData(const utility::device_vector &data) { n_points_ = data.size(); @@ -254,6 +270,12 @@ template int LinearBoundingVolumeHierarchyKNN::SearchNN( thrust::host_vector &indices, thrust::host_vector &distance2) const; +template int LinearBoundingVolumeHierarchyKNN::SearchNN( + const Eigen::Vector3f &query, + float radius, + std::vector &indices, + std::vector &distance2) const; + template bool LinearBoundingVolumeHierarchyKNN::SetRawData( const utility::device_vector &data); diff --git a/src/cupoch/knn/lbvh_knn.h b/src/cupoch/knn/lbvh_knn.h index 4f03739f..2a2c8408 100644 --- a/src/cupoch/knn/lbvh_knn.h +++ b/src/cupoch/knn/lbvh_knn.h @@ -66,6 +66,12 @@ class LinearBoundingVolumeHierarchyKNN { thrust::host_vector &indices, thrust::host_vector &distance2) const; + template + int SearchNN(const T &query, + float radius, + std::vector &indices, + std::vector &distance2) const; + template bool SetRawData(const utility::device_vector &data); diff --git a/src/cupoch/registration/feature.cu b/src/cupoch/registration/feature.cu index 28cc90eb..82044ee6 100644 --- a/src/cupoch/registration/feature.cu +++ b/src/cupoch/registration/feature.cu @@ -20,6 +20,8 @@ **/ #include "cupoch/registration/feature.h" +#include "cupoch/utility/helper.h" + namespace cupoch { namespace registration { @@ -53,16 +55,18 @@ bool Feature::IsEmpty() const { } template -thrust::host_vector> Feature::GetData() +std::vector> Feature::GetData() const { - thrust::host_vector> h_data = data_; + std::vector> h_data(data_.size()); + copy_device_to_host(data_, h_data); return h_data; } template void Feature::SetData( - const thrust::host_vector> &data) { - data_ = data; + const std::vector> &data) { + data_.resize(data.size()); + copy_host_to_device(data, data_); } template class Feature<33>; diff --git a/src/cupoch/registration/feature.h b/src/cupoch/registration/feature.h index c5a93efd..f835c28c 100644 --- a/src/cupoch/registration/feature.h +++ b/src/cupoch/registration/feature.h @@ -45,8 +45,8 @@ class Feature { size_t Dimension() const; size_t Num() const; bool IsEmpty() const; - thrust::host_vector> GetData() const; - void SetData(const thrust::host_vector>& data); + std::vector> GetData() const; + void SetData(const std::vector>& data); public: typedef Eigen::Matrix FeatureType; diff --git a/src/cupoch/utility/helper.h b/src/cupoch/utility/helper.h index f37e9893..b56247cb 100644 --- a/src/cupoch/utility/helper.h +++ b/src/cupoch/utility/helper.h @@ -438,25 +438,25 @@ __host__ __device__ inline thrust::tuple KeyOf(size_t idx, return thrust::make_tuple(x, y, z); } -template +template inline void copy_device_to_host(const utility::device_vector &src, - utility::pinned_host_vector &dist) { + ContainerType &dist) { cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(dist.data()), thrust::raw_pointer_cast(src.data()), src.size() * sizeof(T), cudaMemcpyDeviceToHost)); } -template -inline void copy_host_to_device(const utility::pinned_host_vector &src, +template +inline void copy_host_to_device(const ContainerType &src, utility::device_vector &dist) { cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(dist.data()), thrust::raw_pointer_cast(src.data()), src.size() * sizeof(T), cudaMemcpyHostToDevice)); } -template +template inline void copy_device_to_device(const utility::device_vector &src, - utility::device_vector &dist) { + ContainerType &dist) { cudaSafeCall(cudaMemcpy(thrust::raw_pointer_cast(dist.data()), thrust::raw_pointer_cast(src.data()), src.size() * sizeof(T), cudaMemcpyDeviceToDevice)); diff --git a/src/python/pyproject.toml b/src/python/pyproject.toml index b9daddbe..e8042b04 100644 --- a/src/python/pyproject.toml +++ b/src/python/pyproject.toml @@ -21,8 +21,8 @@ rospy-all = {version = "^0.0.1", optional = true} rosmaster = {version = "^1.15.11", optional = true} rosbag = {version = "^1.15.11", optional = true} transformations = {version = "^2022.9.26", optional = true} - setuptools = "^72.2.0" + [tool.poetry.dev-dependencies] twine = "^3.2.0" wheel = "^0.36.2" diff --git a/src/tests/collision/collision.cpp b/src/tests/collision/collision.cpp index 9cd7ab29..3c20e89a 100644 --- a/src/tests/collision/collision.cpp +++ b/src/tests/collision/collision.cpp @@ -56,13 +56,15 @@ TEST(Collision, VoxelLineSet) { voxel.voxel_size_ = 1.0; voxel.AddVoxel(geometry::Voxel(Eigen::Vector3i(0, 0, 0))); voxel.AddVoxel(geometry::Voxel(Eigen::Vector3i(5, 0, 0))); - thrust::host_vector points; - points.push_back(Eigen::Vector3f(-0.1, -0.1, -0.1)); - points.push_back(Eigen::Vector3f(-0.1, -0.1, 1.1)); - points.push_back(Eigen::Vector3f(1.1, 1.1, 1.1)); - thrust::host_vector lines; - lines.push_back(Eigen::Vector2i(0, 1)); - lines.push_back(Eigen::Vector2i(0, 2)); + std::vector points = { + Eigen::Vector3f(-0.1, -0.1, -0.1), + Eigen::Vector3f(-0.1, -0.1, 1.1), + Eigen::Vector3f(1.1, 1.1, 1.1) + }; + std::vector lines = { + Eigen::Vector2i(0, 1), + Eigen::Vector2i(0, 2) + }; lineset.SetPoints(points); lineset.SetLines(lines); diff --git a/src/tests/geometry/distancetransform.cpp b/src/tests/geometry/distancetransform.cpp index fa975bd4..65b29765 100644 --- a/src/tests/geometry/distancetransform.cpp +++ b/src/tests/geometry/distancetransform.cpp @@ -32,10 +32,10 @@ using namespace unit_test; TEST(DistanceTransform, ComputeVoronoiDiagram) { geometry::VoxelGrid voxelgrid; voxelgrid.voxel_size_ = 1.0; - thrust::host_vector h_keys; + std::vector h_keys; Eigen::Vector3i ref(5, 5, 5); h_keys.push_back(ref); - voxelgrid.SetVoxels(h_keys, thrust::host_vector()); + voxelgrid.SetVoxels(h_keys, std::vector()); geometry::DistanceTransform dt(1.0, 512); dt.ComputeVoronoiDiagram(voxelgrid); auto v = dt.GetVoxel(Eigen::Vector3f(0.0, 0.0, 0.0)); diff --git a/src/tests/geometry/graph.cpp b/src/tests/geometry/graph.cpp index a32daee6..f85cf4c8 100644 --- a/src/tests/geometry/graph.cpp +++ b/src/tests/geometry/graph.cpp @@ -57,7 +57,7 @@ TEST(Graph, Constructor) { TEST(Graph, AddEdge) { geometry::Graph<3> gp; - thrust::host_vector points; + std::vector points; points.push_back({0.0, 0.0, 0.0}); points.push_back({1.0, 0.0, 0.0}); points.push_back({0.0, 1.0, 0.0}); @@ -71,7 +71,7 @@ TEST(Graph, AddEdge) { gp.AddEdge({3, 4}); EXPECT_EQ(gp.lines_.size(), 10); - thrust::host_vector edge_index_offsets = gp.GetEdgeIndexOffsets(); + std::vector edge_index_offsets = gp.GetEdgeIndexOffsets(); EXPECT_EQ(edge_index_offsets.size(), 6); EXPECT_EQ(edge_index_offsets[0], 0); EXPECT_EQ(edge_index_offsets[1], 2); @@ -83,7 +83,7 @@ TEST(Graph, AddEdge) { TEST(Graph, DijkstraPath) { geometry::Graph<3> gp; - thrust::host_vector points; + std::vector points; points.push_back({0.0, 0.0, 0.0}); points.push_back({1.0, 0.0, 0.0}); points.push_back({0.0, 1.0, 0.0}); diff --git a/src/tests/geometry/image.cpp b/src/tests/geometry/image.cpp index 2265fd22..b366a353 100644 --- a/src/tests/geometry/image.cpp +++ b/src/tests/geometry/image.cpp @@ -200,7 +200,7 @@ TEST(Image, CreateDepthToCameraDistanceMultiplierFloatImage) { void TEST_CreateFloatImage( const int& num_of_channels, const int& bytes_per_channel, - const thrust::host_vector& ref, + const std::vector& ref, const geometry::Image::ColorToIntensityConversionType& type) { geometry::Image image; @@ -211,7 +211,7 @@ void TEST_CreateFloatImage( image.Prepare(width, height, num_of_channels, bytes_per_channel); - thrust::host_vector data(image.data_.size()); + std::vector data(image.data_.size()); Rand(data, 0, 255, 0); image.SetData(data); @@ -236,7 +236,7 @@ TEST(Image, CreateFloatImage_1_1) { 162, 34, 63, 183, 182, 54, 63, 145, 144, 16, 62, 155, 154, 26, 63, 129, 128, 128, 60, 246, 244, 116, 62, 137, 136, 8, 62, 207, 205, 77, 63, 157, 156, 28, 62}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_CreateFloatImage(1, 1, ref, ConversionType::Weighted); @@ -252,7 +252,7 @@ TEST(Image, CreateFloatImage_1_2) { 0, 56, 151, 70, 0, 162, 5, 71, 0, 125, 120, 71, 0, 74, 68, 71, 0, 134, 68, 71, 0, 102, 99, 71, 0, 144, 178, 70, 0, 205, 106, 71, 0, 17, 114, 71}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_CreateFloatImage(1, 2, ref, ConversionType::Weighted); @@ -269,7 +269,7 @@ TEST(Image, CreateFloatImage_1_4) { 137, 95, 193, 130, 170, 135, 10, 111, 237, 237, 183, 72, 188, 163, 90, 175, 42, 112, 224, 211, 84, 58, 227, 89, 175, 243, 150, 167, 218, 112, 235, 101, 207, 174, 232}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_CreateFloatImage(1, 4, ref, ConversionType::Weighted); @@ -286,7 +286,7 @@ TEST(Image, CreateFloatImage_3_1_Weighted) { 12, 35, 63, 122, 21, 90, 62, 101, 168, 243, 62, 209, 97, 143, 62, 10, 228, 61, 63, 224, 255, 239, 62, 59, 33, 29, 63, 197, 186, 3, 63, 145, 27, 72, 63}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_CreateFloatImage(3, 1, ref, ConversionType::Weighted); @@ -303,7 +303,7 @@ TEST(Image, CreateFloatImage_3_1_Equal) { 12, 35, 63, 122, 21, 90, 62, 101, 168, 243, 62, 209, 97, 143, 62, 10, 228, 61, 63, 224, 255, 239, 62, 59, 33, 29, 63, 197, 186, 3, 63, 145, 27, 72, 63}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_CreateFloatImage(3, 1, ref, ConversionType::Equal); @@ -320,7 +320,7 @@ TEST(Image, CreateFloatImage_3_2_Weighted) { 235, 76, 71, 31, 111, 86, 71, 27, 105, 148, 70, 71, 196, 219, 70, 12, 108, 22, 71, 197, 41, 183, 70, 225, 5, 23, 71, 210, 181, 85, 71, 101, 14, 28, 71}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_CreateFloatImage(3, 2, ref, ConversionType::Weighted); @@ -337,7 +337,7 @@ TEST(Image, CreateFloatImage_3_2_Equal) { 235, 76, 71, 31, 111, 86, 71, 27, 105, 148, 70, 71, 196, 219, 70, 12, 108, 22, 71, 197, 41, 183, 70, 225, 5, 23, 71, 210, 181, 85, 71, 101, 14, 28, 71}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_CreateFloatImage(3, 2, ref, ConversionType::Equal); @@ -354,7 +354,7 @@ TEST(Image, CreateFloatImage_3_4_Weighted) { 111, 82, 249, 14, 45, 72, 210, 222, 97, 25, 247, 179, 223, 15, 114, 245, 201, 149, 76, 224, 3, 24, 64, 17, 103, 98, 222, 145, 236, 94, 233, 36, 85, 141, 233}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_CreateFloatImage(3, 4, ref, ConversionType::Weighted); @@ -371,7 +371,7 @@ TEST(Image, CreateFloatImage_3_4_Equal) { 111, 82, 249, 14, 45, 72, 210, 222, 97, 25, 247, 179, 223, 15, 114, 245, 201, 149, 76, 224, 3, 24, 64, 17, 103, 98, 222, 145, 236, 94, 233, 36, 85, 141, 233}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_CreateFloatImage(3, 4, ref, ConversionType::Equal); @@ -388,7 +388,7 @@ TEST(Image, ConvertDepthToFloatImage) { 137, 38, 58, 79, 25, 59, 58, 198, 8, 20, 57, 126, 80, 30, 58, 6, 150, 131, 55, 251, 213, 122, 57, 102, 207, 11, 57, 69, 190, 82, 58, 215, 94, 32, 57}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); geometry::Image image; @@ -401,7 +401,7 @@ TEST(Image, ConvertDepthToFloatImage) { image.Prepare(width, height, num_of_channels, bytes_per_channel); - thrust::host_vector data(image.data_.size()); + std::vector data(image.data_.size()); Rand(data, 0, 255, 0); image.SetData(data); @@ -423,7 +423,7 @@ TEST(Image, TransposeUint8) { 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17 }; - thrust::host_vector input; + std::vector input; for (int i = 0; i < 18; ++i) input.push_back(raw_input[i]); uint8_t raw_transposed_ref[] = { 0, 6, 12, @@ -433,7 +433,7 @@ TEST(Image, TransposeUint8) { 4, 10, 16, 5, 11, 17 }; - thrust::host_vector transposed_ref; + std::vector transposed_ref; for (int i = 0; i < 18; ++i) transposed_ref.push_back(raw_transposed_ref[i]); // clang-format on @@ -464,7 +464,7 @@ TEST(Image, TransposeFloat) { 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17 }; - thrust::host_vector input; + std::vector input; for (int i = 0; i < 18; ++i) input.push_back(raw_input[i]); float raw_transposed_ref[] = { 0, 6, 12, @@ -474,7 +474,7 @@ TEST(Image, TransposeFloat) { 4, 10, 16, 5, 11, 17 }; - thrust::host_vector transposed_ref; + std::vector transposed_ref; for (int i = 0; i < 18; ++i) transposed_ref.push_back(raw_transposed_ref[i]); // clang-format on @@ -488,7 +488,7 @@ TEST(Image, TransposeFloat) { image.Prepare(width, height, num_of_channels, bytes_per_channel); const uint8_t* input_uint8_ptr = reinterpret_cast(input.data()); - thrust::host_vector input_uint8( + std::vector input_uint8( input_uint8_ptr, input_uint8_ptr + image.data_.size()); image.SetData(input_uint8); @@ -499,11 +499,11 @@ TEST(Image, TransposeFloat) { EXPECT_EQ(num_of_channels, transposed_image->num_of_channels_); EXPECT_EQ(int(sizeof(float)), transposed_image->bytes_per_channel_); - thrust::host_vector transposed_host_data = + std::vector transposed_host_data = transposed_image->GetData(); const float* transpose_image_floats = reinterpret_cast(transposed_host_data.data()); - thrust::host_vector transpose_image_data( + std::vector transpose_image_data( transpose_image_floats, transpose_image_floats + transposed_ref.size()); ExpectEQ(transposed_ref, transpose_image_data); @@ -517,14 +517,14 @@ TEST(Image, FlipVerticalImage) { 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17 }; - thrust::host_vector input; + std::vector input; for (int i = 0; i < 18; ++i) input.push_back(raw_input[i]); uint8_t raw_flipped[] = { 12, 13, 14, 15, 16, 17, 6, 7, 8, 9, 10, 11, 0, 1, 2, 3, 4, 5, }; - thrust::host_vector flipped; + std::vector flipped; for (int i = 0; i < 18; ++i) flipped.push_back(raw_flipped[i]); // clang-format on @@ -555,14 +555,14 @@ TEST(Image, FlipHorizontalImage) { 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17 }; - thrust::host_vector input; + std::vector input; for (int i = 0; i < 18; ++i) input.push_back(raw_input[i]); uint8_t raw_flipped[] = { 5, 4, 3, 2, 1, 0, 11, 10, 9, 8, 7, 6, 17, 16, 15, 14, 13, 12 }; - thrust::host_vector flipped; + std::vector flipped; for (int i = 0; i < 18; ++i) flipped.push_back(raw_flipped[i]); // clang-format on @@ -585,7 +585,7 @@ TEST(Image, FlipHorizontalImage) { ExpectEQ(flipped, flip_image->GetData()); } -void TEST_Filter(const thrust::host_vector& ref, +void TEST_Filter(const std::vector& ref, const geometry::Image::FilterType& filter) { geometry::Image image; @@ -597,7 +597,7 @@ void TEST_Filter(const thrust::host_vector& ref, image.Prepare(width, height, num_of_channels, bytes_per_channel); - thrust::host_vector data(image.data_.size()); + std::vector data(image.data_.size()); Rand(data, 0, 255, 0); image.SetData(data); @@ -624,7 +624,7 @@ TEST(Image, Filter_Gaussian3) { 91, 77, 233, 2, 196, 171, 233, 229, 149, 243, 233, 12, 159, 128, 233, 36, 49, 20, 226, 223, 39, 141, 226, 137, 164, 52, 234, 108, 176, 182, 234, 146, 238, 64, 234}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_Filter(ref, FilterType::Gaussian3); @@ -641,7 +641,7 @@ TEST(Image, Filter_Gaussian5) { 73, 101, 233, 15, 186, 202, 233, 62, 231, 242, 233, 76, 236, 159, 233, 35, 111, 205, 231, 102, 26, 76, 233, 254, 241, 44, 234, 33, 174, 126, 234, 84, 234, 47, 234}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_Filter(ref, FilterType::Gaussian5); @@ -658,7 +658,7 @@ TEST(Image, Filter_Gaussian7) { 49, 127, 233, 20, 166, 194, 233, 176, 46, 222, 233, 33, 207, 168, 233, 186, 237, 232, 232, 98, 40, 161, 233, 128, 206, 18, 234, 109, 135, 55, 234, 187, 97, 17, 234}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_Filter(ref, FilterType::Gaussian7); @@ -675,7 +675,7 @@ TEST(Image, Filter_Sobel3Dx) { 133, 106, 99, 73, 45, 10, 235, 101, 207, 174, 232, 44, 100, 107, 107, 28, 239, 8, 228, 119, 32, 52, 97, 114, 163, 52, 236, 140, 27, 131, 233, 33, 139, 48, 108}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_Filter(ref, FilterType::Sobel3Dx); @@ -692,7 +692,7 @@ TEST(Image, Filter_Sobel3Dy) { 88, 77, 107, 189, 46, 10, 235, 229, 149, 243, 235, 12, 159, 128, 235, 189, 150, 69, 227, 36, 53, 188, 227, 97, 219, 112, 235, 229, 149, 243, 235, 12, 159, 128, 235}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); TEST_Filter(ref, FilterType::Sobel3Dy); @@ -709,7 +709,7 @@ TEST(Image, FilterHorizontal) { 247, 230, 215, 97, 137, 95, 192, 72, 188, 163, 89, 108, 154, 117, 90, 211, 150, 69, 226, 40, 53, 188, 226, 97, 219, 112, 234, 229, 149, 243, 234, 12, 159, 128, 234}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 100; ++i) ref.push_back(raw_ref[i]); geometry::Image image; @@ -722,13 +722,13 @@ TEST(Image, FilterHorizontal) { image.Prepare(width, height, num_of_channels, bytes_per_channel); - thrust::host_vector data(image.data_.size()); + std::vector data(image.data_.size()); Rand(data, 0, 255, 0); image.SetData(data); auto float_image = image.CreateFloatImage(); - thrust::host_vector Gaussian3(3); + std::vector Gaussian3(3); Gaussian3[0] = 0.25; Gaussian3[1] = 0.5; Gaussian3[2] = 0.25; @@ -747,7 +747,7 @@ TEST(Image, Downsample) { // reference data used to validate the filtering of an image uint8_t raw_ref[] = {172, 41, 59, 204, 93, 130, 242, 232, 22, 91, 205, 233, 49, 169, 227, 87}; - thrust::host_vector ref; + std::vector ref; for (int i = 0; i < 16; ++i) ref.push_back(raw_ref[i]); geometry::Image image; @@ -760,7 +760,7 @@ TEST(Image, Downsample) { image.Prepare(width, height, num_of_channels, bytes_per_channel); - thrust::host_vector data(image.data_.size()); + std::vector data(image.data_.size()); Rand(data, 0, 255, 0); image.SetData(data); diff --git a/src/tests/geometry/laserscanbuffer.cpp b/src/tests/geometry/laserscanbuffer.cpp index 6758a7a0..f26ab2ae 100644 --- a/src/tests/geometry/laserscanbuffer.cpp +++ b/src/tests/geometry/laserscanbuffer.cpp @@ -51,7 +51,7 @@ TEST(LaserScanBuffer, AddRanges) { EXPECT_EQ(scan.num_steps_, 100); EXPECT_EQ(scan.bottom_, 0); - utility::pinned_host_vector hvec(100, 1.0); + std::vector hvec(100, 1.0); scan.AddRanges(hvec); EXPECT_EQ(scan.num_steps_, 100); EXPECT_EQ(scan.bottom_, 1); @@ -81,7 +81,7 @@ TEST(LaserScanBuffer, AddRanges) { TEST(LaserScanBuffer, RangeFilter) { geometry::LaserScanBuffer scan(5); - utility::pinned_host_vector hvec; + std::vector hvec; hvec.push_back(1.0); hvec.push_back(2.0); hvec.push_back(3.0); diff --git a/src/tests/geometry/lineset.cpp b/src/tests/geometry/lineset.cpp index 7adc3826..e1d4d9d3 100644 --- a/src/tests/geometry/lineset.cpp +++ b/src/tests/geometry/lineset.cpp @@ -63,9 +63,9 @@ TEST(LineSet, Clear) { geometry::LineSet<3> ls; - thrust::host_vector points(size); - thrust::host_vector lines(size); - thrust::host_vector colors(size); + std::vector points(size); + std::vector lines(size); + std::vector colors(size); Rand(points, dmin, dmax, 0); Rand(lines, imin, imax, 0); Rand(colors, dmin, dmax, 0); diff --git a/src/tests/geometry/occupancygrid.cpp b/src/tests/geometry/occupancygrid.cpp index 86617dbc..60bf3c26 100644 --- a/src/tests/geometry/occupancygrid.cpp +++ b/src/tests/geometry/occupancygrid.cpp @@ -68,7 +68,7 @@ TEST(OccupancyGrid, Insert) { auto occupancy_grid = std::make_shared(); occupancy_grid->origin_ = Eigen::Vector3f(-0.5, -0.5, 0); occupancy_grid->voxel_size_ = 1.0; - utility::pinned_host_vector host_points; + std::vector host_points; host_points.push_back({0.0, 0.0, 3.5}); occupancy_grid->Insert(host_points, Eigen::Vector3f::Zero()); EXPECT_EQ(occupancy_grid->ExtractKnownVoxels()->size(), 4); diff --git a/src/tests/geometry/pointcloud.cpp b/src/tests/geometry/pointcloud.cpp index d66a25c9..c2c2fe9f 100644 --- a/src/tests/geometry/pointcloud.cpp +++ b/src/tests/geometry/pointcloud.cpp @@ -60,11 +60,11 @@ TEST(PointCloud, Clear) { geometry::PointCloud pc; - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); - thrust::host_vector normals(size); + std::vector normals(size); Rand(normals, vmin, vmax, 0); - thrust::host_vector colors(size); + std::vector colors(size); Rand(colors, vmin, vmax, 0); pc.SetPoints(points); pc.SetNormals(normals); @@ -101,7 +101,7 @@ TEST(PointCloud, IsEmpty) { EXPECT_TRUE(pc.IsEmpty()); - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); @@ -116,7 +116,7 @@ TEST(PointCloud, GetMinBound) { geometry::PointCloud pc; - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); @@ -132,7 +132,7 @@ TEST(PointCloud, GetMaxBound) { geometry::PointCloud pc; - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); @@ -147,11 +147,11 @@ TEST(PointCloud, Transform) { Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(1000.0, 1000.0, 1000.0); - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); - thrust::host_vector normals(size); + std::vector normals(size); normals.resize(size); Rand(normals, vmin, vmax, 0); pc.SetNormals(normals); @@ -178,7 +178,7 @@ TEST(PointCloud, GetOrientedBoundingBox) { geometry::OrientedBoundingBox obb; // Valid 4 points - thrust::host_vector points; + std::vector points; points.push_back({0, 0, 0}); points.push_back({0, 0, 1}); points.push_back({0, 1, 0}); @@ -203,9 +203,9 @@ TEST(PointCloud, GetOrientedBoundingBox) { EXPECT_EQ(obb.color_, Eigen::Vector3f(0, 0, 0)); EXPECT_EQ(obb.R_, Eigen::Matrix3f::Identity()); const auto obb_pts_arr = obb.GetBoxPoints(); - thrust::host_vector obb_points(obb_pts_arr.begin(), obb_pts_arr.end()); + std::vector obb_points(obb_pts_arr.begin(), obb_pts_arr.end()); sort::Do(obb_points); - thrust::host_vector ref_points; + std::vector ref_points; ref_points.push_back({0, 0, 0}); ref_points.push_back({0, 0, 1}); ref_points.push_back({0, 2, 0}); @@ -225,7 +225,7 @@ TEST(PointCloud, HasPoints) { EXPECT_FALSE(pc.HasPoints()); - thrust::host_vector points(size); + std::vector points(size); pc.SetPoints(points); EXPECT_TRUE(pc.HasPoints()); @@ -238,9 +238,9 @@ TEST(PointCloud, HasNormals) { EXPECT_FALSE(pc.HasNormals()); - thrust::host_vector points(size); + std::vector points(size); pc.SetPoints(points); - thrust::host_vector normals(size); + std::vector normals(size); pc.SetNormals(normals); EXPECT_TRUE(pc.HasNormals()); @@ -253,16 +253,16 @@ TEST(PointCloud, HasColors) { EXPECT_FALSE(pc.HasColors()); - thrust::host_vector points(size); + std::vector points(size); pc.SetPoints(points); - thrust::host_vector colors(size); + std::vector colors(size); pc.SetColors(colors); EXPECT_TRUE(pc.HasColors()); } TEST(PointCloud, NormalizeNormals) { - thrust::host_vector ref; + std::vector ref; ref.push_back(Vector3f(0.692861, 0.323767, 0.644296)); ref.push_back(Vector3f(0.650010, 0.742869, 0.160101)); ref.push_back(Vector3f(0.379563, 0.870761, 0.312581)); @@ -291,7 +291,7 @@ TEST(PointCloud, NormalizeNormals) { geometry::PointCloud pc; - thrust::host_vector normals(size); + std::vector normals(size); Rand(normals, vmin, vmax, 0); pc.SetNormals(normals); @@ -301,7 +301,7 @@ TEST(PointCloud, NormalizeNormals) { } TEST(PointCloud, SelectByIndex) { - thrust::host_vector ref_idx; + std::vector ref_idx; ref_idx.push_back(3); ref_idx.push_back(10); ref_idx.push_back(24); @@ -319,8 +319,8 @@ TEST(PointCloud, SelectByIndex) { Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(1000.0, 1000.0, 1000.0); - thrust::host_vector points(size); - thrust::host_vector ref_pt; + std::vector points(size); + std::vector ref_pt; Rand(points, vmin, vmax, 0); pc.SetPoints(points); for (auto i: ref_idx) ref_pt.push_back(points[i]); @@ -334,7 +334,7 @@ TEST(PointCloud, SelectByIndex) { } TEST(PointCloud, SelectByMask) { - thrust::host_vector ref_idx; + std::vector ref_idx; ref_idx.push_back(3); ref_idx.push_back(10); ref_idx.push_back(24); @@ -352,9 +352,9 @@ TEST(PointCloud, SelectByMask) { Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(1000.0, 1000.0, 1000.0); - thrust::host_vector points(size); - thrust::host_vector ref_pt; - thrust::host_vector ref_mask(size, false); + std::vector points(size); + std::vector ref_pt; + std::vector ref_mask(size, false); Rand(points, vmin, vmax, 0); pc.SetPoints(points); for (auto i: ref_idx) ref_pt.push_back(points[i]); @@ -369,7 +369,7 @@ TEST(PointCloud, SelectByMask) { } TEST(PointCloud, VoxelDownSample) { - thrust::host_vector ref_points; + std::vector ref_points; ref_points.push_back(Vector3f(19.607843, 454.901961, 62.745098)); ref_points.push_back(Vector3f(66.666667, 949.019608, 525.490196)); ref_points.push_back(Vector3f(82.352941, 192.156863, 662.745098)); @@ -391,7 +391,7 @@ TEST(PointCloud, VoxelDownSample) { ref_points.push_back(Vector3f(890.196078, 345.098039, 62.745098)); ref_points.push_back(Vector3f(913.725490, 635.294118, 713.725490)); - thrust::host_vector ref_normals; + std::vector ref_normals; ref_normals.push_back(Vector3f(0.042660, 0.989719, 0.136513)); ref_normals.push_back(Vector3f(0.061340, 0.873191, 0.483503)); ref_normals.push_back(Vector3f(0.103335, 0.972118, 0.210498)); @@ -413,7 +413,7 @@ TEST(PointCloud, VoxelDownSample) { ref_normals.push_back(Vector3f(0.692861, 0.323767, 0.644296)); ref_normals.push_back(Vector3f(0.930383, 0.360677, 0.065578)); - thrust::host_vector ref_colors; + std::vector ref_colors; ref_colors.push_back(Vector3f(5.000000, 116.000000, 16.000000)); ref_colors.push_back(Vector3f(17.000000, 242.000000, 134.000000)); ref_colors.push_back(Vector3f(21.000000, 49.000000, 169.000000)); @@ -438,13 +438,13 @@ TEST(PointCloud, VoxelDownSample) { size_t size = 20; geometry::PointCloud pc; - thrust::host_vector points(size); + std::vector points(size); Rand(points, Zero3f, Vector3f(1000.0, 1000.0, 1000.0), 0); pc.SetPoints(points); - thrust::host_vector normals(size); + std::vector normals(size); Rand(normals, Zero3f, Vector3f(10.0, 10.0, 10.0), 0); pc.SetNormals(normals); - thrust::host_vector colors(size); + std::vector colors(size); Rand(colors, Zero3f, Vector3f(255.0, 255.0, 255.0), 0); pc.SetColors(colors); @@ -469,7 +469,7 @@ TEST(PointCloud, VoxelDownSample) { } TEST(PointCloud, UniformDownSample) { - thrust::host_vector ref; + std::vector ref; ref.push_back(Vector3f(839.215686, 392.156863, 780.392157)); ref.push_back(Vector3f(364.705882, 509.803922, 949.019608)); ref.push_back(Vector3f(152.941176, 400.000000, 129.411765)); @@ -502,7 +502,7 @@ TEST(PointCloud, UniformDownSample) { Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(1000.0, 1000.0, 1000.0); - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); @@ -519,7 +519,7 @@ TEST(PointCloud, CropPointCloud) { Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(1000.0, 1000.0, 1000.0); - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); @@ -533,7 +533,7 @@ TEST(PointCloud, CropPointCloud) { } TEST(PointCloud, EstimateNormals) { - thrust::host_vector ref; + std::vector ref; ref.push_back(Vector3f(0.282003, 0.866394, 0.412111)); ref.push_back(Vector3f(0.550791, 0.829572, -0.091869)); ref.push_back(Vector3f(0.076085, -0.974168, 0.212620)); @@ -581,12 +581,12 @@ TEST(PointCloud, EstimateNormals) { Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(1000.0, 1000.0, 1000.0); - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); pc.EstimateNormals(knn::KDTreeSearchParamKNN()); - thrust::host_vector normals = pc.GetNormals(); + std::vector normals = pc.GetNormals(); for (size_t idx = 0; idx < ref.size(); ++idx) { if ((ref[idx](0) < 0 && normals[idx](0) > 0) || (ref[idx](0) > 0 && normals[idx](0) < 0)) { @@ -597,7 +597,7 @@ TEST(PointCloud, EstimateNormals) { } TEST(PointCloud, OrientNormalsToAlignWithDirection) { - thrust::host_vector ref; + std::vector ref; ref.push_back(Vector3f(0.282003, 0.866394, 0.412111)); ref.push_back(Vector3f(0.550791, 0.829572, -0.091869)); ref.push_back(Vector3f(0.076085, -0.974168, 0.212620)); @@ -645,7 +645,7 @@ TEST(PointCloud, OrientNormalsToAlignWithDirection) { Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(1000.0, 1000.0, 1000.0); - thrust::host_vector points; + std::vector points; points.resize(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); @@ -658,7 +658,7 @@ TEST(PointCloud, OrientNormalsToAlignWithDirection) { TEST(PointCloud, SegmentPlaneKnownPlane) { // Points sampled from the plane x + y + z + 1 = 0 - thrust::host_vector ref_points; + std::vector ref_points; ref_points.push_back(Eigen::Vector3f({1.0, 1.0, -1.0})); ref_points.push_back(Eigen::Vector3f({2.0, 2.0, -5.0})); ref_points.push_back(Eigen::Vector3f({-1.0, -1.0, 1.0})); @@ -674,7 +674,7 @@ TEST(PointCloud, SegmentPlaneKnownPlane) { } TEST(PointCloud, RemoveRadiusOutliers) { - thrust::host_vector points; + std::vector points; points.push_back(Eigen::Vector3f({0.0, 0.0, 0.0})); points.push_back(Eigen::Vector3f({1.0, 0.0, 0.0})); points.push_back(Eigen::Vector3f({-1.0, 0.0, 0.0})); diff --git a/src/tests/geometry/trianglemesh.cpp b/src/tests/geometry/trianglemesh.cpp index 41f0097e..b0d5d53f 100644 --- a/src/tests/geometry/trianglemesh.cpp +++ b/src/tests/geometry/trianglemesh.cpp @@ -80,11 +80,11 @@ TEST(TriangleMesh, Clear) { geometry::TriangleMesh tm; - thrust::host_vector vertices(size); - thrust::host_vector vertex_normals(size); - thrust::host_vector vertex_colors(size); - thrust::host_vector triangles(size); - thrust::host_vector triangle_normals(size); + std::vector vertices(size); + std::vector vertex_normals(size); + std::vector vertex_colors(size); + std::vector triangles(size); + std::vector triangle_normals(size); Rand(vertices, dmin, dmax, 0); tm.SetVertices(vertices); @@ -130,7 +130,7 @@ TEST(TriangleMesh, IsEmpty) { EXPECT_TRUE(tm.IsEmpty()); - thrust::host_vector vertices(size); + std::vector vertices(size); tm.SetVertices(vertices); EXPECT_FALSE(tm.IsEmpty()); @@ -144,7 +144,7 @@ TEST(TriangleMesh, GetMinBound) { geometry::TriangleMesh tm; - thrust::host_vector vertices(size); + std::vector vertices(size); Rand(vertices, dmin, dmax, 0); tm.SetVertices(vertices); @@ -159,7 +159,7 @@ TEST(TriangleMesh, GetMaxBound) { geometry::TriangleMesh tm; - thrust::host_vector vertices(size); + std::vector vertices(size); Rand(vertices, dmin, dmax, 0); tm.SetVertices(vertices); @@ -178,11 +178,11 @@ TEST(TriangleMesh, OperatorAppend) { geometry::TriangleMesh tm0; geometry::TriangleMesh tm1; - thrust::host_vector vertices0(size); - thrust::host_vector vertex_normals0(size); - thrust::host_vector vertex_colors0(size); - thrust::host_vector triangles0(size); - thrust::host_vector triangle_normals0(size); + std::vector vertices0(size); + std::vector vertex_normals0(size); + std::vector vertex_colors0(size); + std::vector triangles0(size); + std::vector triangle_normals0(size); Rand(vertices0, dmin, dmax, 0); Rand(vertex_normals0, dmin, dmax, 0); Rand(vertex_colors0, dmin, dmax, 0); @@ -194,11 +194,11 @@ TEST(TriangleMesh, OperatorAppend) { tm0.SetTriangles(triangles0); tm0.SetTriangleNormals(triangle_normals0); - thrust::host_vector vertices1(size); - thrust::host_vector vertex_normals1(size); - thrust::host_vector vertex_colors1(size); - thrust::host_vector triangles1(size); - thrust::host_vector triangle_normals1(size); + std::vector vertices1(size); + std::vector vertex_normals1(size); + std::vector vertex_colors1(size); + std::vector triangles1(size); + std::vector triangle_normals1(size); Rand(vertices1, dmin, dmax, 0); Rand(vertex_normals1, dmin, dmax, 0); Rand(vertex_colors1, dmin, dmax, 0); @@ -213,11 +213,11 @@ TEST(TriangleMesh, OperatorAppend) { geometry::TriangleMesh tm(tm0); tm += tm1; - thrust::host_vector vertices = tm.GetVertices(); - thrust::host_vector vertex_normals = tm.GetVertexNormals(); - thrust::host_vector vertex_colors = tm.GetVertexColors(); - thrust::host_vector triangles = tm.GetTriangles(); - thrust::host_vector triangle_normals = tm.GetTriangleNormals(); + std::vector vertices = tm.GetVertices(); + std::vector vertex_normals = tm.GetVertexNormals(); + std::vector vertex_colors = tm.GetVertexColors(); + std::vector triangles = tm.GetTriangles(); + std::vector triangle_normals = tm.GetTriangleNormals(); EXPECT_EQ(2 * size, tm.vertices_.size()); for (size_t i = 0; i < size; i++) { @@ -266,11 +266,11 @@ TEST(TriangleMesh, OperatorADD) { geometry::TriangleMesh tm0; geometry::TriangleMesh tm1; - thrust::host_vector vertices0(size); - thrust::host_vector vertex_normals0(size); - thrust::host_vector vertex_colors0(size); - thrust::host_vector triangles0(size); - thrust::host_vector triangle_normals0(size); + std::vector vertices0(size); + std::vector vertex_normals0(size); + std::vector vertex_colors0(size); + std::vector triangles0(size); + std::vector triangle_normals0(size); Rand(vertices0, dmin, dmax, 0); Rand(vertex_normals0, dmin, dmax, 0); Rand(vertex_colors0, dmin, dmax, 0); @@ -282,11 +282,11 @@ TEST(TriangleMesh, OperatorADD) { tm0.SetTriangles(triangles0); tm0.SetTriangleNormals(triangle_normals0); - thrust::host_vector vertices1(size); - thrust::host_vector vertex_normals1(size); - thrust::host_vector vertex_colors1(size); - thrust::host_vector triangles1(size); - thrust::host_vector triangle_normals1(size); + std::vector vertices1(size); + std::vector vertex_normals1(size); + std::vector vertex_colors1(size); + std::vector triangles1(size); + std::vector triangle_normals1(size); Rand(vertices1, dmin, dmax, 0); Rand(vertex_normals1, dmin, dmax, 0); Rand(vertex_colors1, dmin, dmax, 0); @@ -300,11 +300,11 @@ TEST(TriangleMesh, OperatorADD) { geometry::TriangleMesh tm = tm0 + tm1; - thrust::host_vector vertices = tm.GetVertices(); - thrust::host_vector vertex_normals = tm.GetVertexNormals(); - thrust::host_vector vertex_colors = tm.GetVertexColors(); - thrust::host_vector triangles = tm.GetTriangles(); - thrust::host_vector triangle_normals = tm.GetTriangleNormals(); + std::vector vertices = tm.GetVertices(); + std::vector vertex_normals = tm.GetVertexNormals(); + std::vector vertex_colors = tm.GetVertexColors(); + std::vector triangles = tm.GetTriangles(); + std::vector triangle_normals = tm.GetTriangleNormals(); EXPECT_EQ(2 * size, tm.vertices_.size()); for (size_t i = 0; i < size; i++) { @@ -367,7 +367,7 @@ TEST(TriangleMesh, ComputeTriangleNormals) { {-0.085377, -0.916925, 0.389820}, {0.787892, 0.611808, -0.070127}, {0.788022, 0.488544, 0.374628}}; - thrust::host_vector ref(25); + std::vector ref(25); for (int i = 0; i < 25; ++i) ref[i] = ref_raw[i]; size_t size = 25; @@ -380,11 +380,11 @@ TEST(TriangleMesh, ComputeTriangleNormals) { geometry::TriangleMesh tm; - thrust::host_vector vertices(size); + std::vector vertices(size); Rand(vertices, dmin, dmax, 0); tm.SetVertices(vertices); - thrust::host_vector triangles; + std::vector triangles; for (size_t i = 0; i < size; i++) triangles.push_back(Vector3i(i, (i + 1) % size, (i + 2) % size)); tm.SetTriangles(triangles); @@ -409,7 +409,7 @@ TEST(TriangleMesh, ComputeVertexNormals) { {0.361530, 0.784805, -0.503366}, {0.429700, 0.646636, -0.630253}, {-0.264834, -0.963970, -0.025005}, {0.940214, -0.336158, -0.054732}, {0.862650, 0.449603, 0.231714}}; - thrust::host_vector ref(25); + std::vector ref(25); for (int i = 0; i < 25; ++i) ref[i] = ref_raw[i]; size_t size = 25; @@ -422,11 +422,11 @@ TEST(TriangleMesh, ComputeVertexNormals) { geometry::TriangleMesh tm; - thrust::host_vector vertices(size); + std::vector vertices(size); Rand(vertices, dmin, dmax, 0); tm.SetVertices(vertices); - thrust::host_vector triangles; + std::vector triangles; for (size_t i = 0; i < size; i++) triangles.push_back(Vector3i(i, (i + 1) % size, (i + 2) % size)); tm.SetTriangles(triangles); @@ -443,7 +443,7 @@ TEST(TriangleMesh, ComputeEdgeList) { Eigen::Vector3f C(-1, 1, 0); // 2 Eigen::Vector3f D(-1, -1, 0); // 3 Eigen::Vector3f E(1, -1, 0); // 4 - thrust::host_vector vertices; + std::vector vertices; vertices.push_back(A); vertices.push_back(B); vertices.push_back(C); @@ -452,7 +452,7 @@ TEST(TriangleMesh, ComputeEdgeList) { geometry::TriangleMesh tm; tm.SetVertices(vertices); - thrust::host_vector triangles; + std::vector triangles; triangles.push_back(Eigen::Vector3i(0, 1, 2)); triangles.push_back(Eigen::Vector3i(0, 2, 3)); triangles.push_back(Eigen::Vector3i(0, 3, 4)); @@ -464,7 +464,7 @@ TEST(TriangleMesh, ComputeEdgeList) { tm.ComputeEdgeList(); EXPECT_TRUE(tm.HasEdgeList()); - thrust::host_vector ref; + std::vector ref; ref.push_back({0, 1}); ref.push_back({0, 2}); ref.push_back({0, 3}); @@ -511,7 +511,7 @@ TEST(TriangleMesh, Purge) { {847.058824, 262.745098, 537.254902}, {372.549020, 756.862745, 509.803922}, {666.666667, 529.411765, 39.215686}}; - thrust::host_vector ref_vertices(24); + std::vector ref_vertices(24); for (int i = 0; i < 24; ++i) ref_vertices[i] = ref_vertices_raw[i]; Vector3f ref_vertex_normals_raw[] = {{839.215686, 392.156863, 780.392157}, @@ -538,7 +538,7 @@ TEST(TriangleMesh, Purge) { {847.058824, 262.745098, 537.254902}, {372.549020, 756.862745, 509.803922}, {666.666667, 529.411765, 39.215686}}; - thrust::host_vector ref_vertex_normals(24); + std::vector ref_vertex_normals(24); for (int i = 0; i < 24; ++i) ref_vertex_normals[i] = ref_vertex_normals_raw[i]; @@ -566,7 +566,7 @@ TEST(TriangleMesh, Purge) { {847.058824, 262.745098, 537.254902}, {372.549020, 756.862745, 509.803922}, {666.666667, 529.411765, 39.215686}}; - thrust::host_vector ref_vertex_colors(24); + std::vector ref_vertex_colors(24); for (int i = 0; i < 24; ++i) ref_vertex_colors[i] = ref_vertex_colors_raw[i]; @@ -576,7 +576,7 @@ TEST(TriangleMesh, Purge) { {7, 15, 12}, {11, 23, 6}, {9, 21, 6}, {8, 19, 22}, {1, 22, 12}, {1, 4, 15}, {21, 8, 1}, {0, 10, 1}, {5, 23, 21}, {20, 6, 12}, {8, 18, 12}, {16, 12, 0}}; - thrust::host_vector ref_triangles(22); + std::vector ref_triangles(22); for (int i = 0; i < 22; ++i) ref_triangles[i] = ref_triangles_raw[i]; Vector3f ref_triangle_normals_raw[] = {{839.215686, 392.156863, 780.392157}, @@ -601,7 +601,7 @@ TEST(TriangleMesh, Purge) { {847.058824, 262.745098, 537.254902}, {372.549020, 756.862745, 509.803922}, {666.666667, 529.411765, 39.215686}}; - thrust::host_vector ref_triangle_normals(22); + std::vector ref_triangle_normals(22); for (int i = 0; i < 22; ++i) ref_triangle_normals[i] = ref_triangle_normals_raw[i]; @@ -616,11 +616,11 @@ TEST(TriangleMesh, Purge) { geometry::TriangleMesh tm0; geometry::TriangleMesh tm1; - thrust::host_vector vertices(size); - thrust::host_vector vertex_normals(size); - thrust::host_vector vertex_colors(size); - thrust::host_vector triangles(size); - thrust::host_vector triangle_normals(size); + std::vector vertices(size); + std::vector vertex_normals(size); + std::vector vertex_colors(size); + std::vector triangles(size); + std::vector triangle_normals(size); Rand(vertices, dmin, dmax, 0); Rand(vertex_normals, dmin, dmax, 0); Rand(vertex_colors, dmin, dmax, 0); @@ -685,11 +685,11 @@ TEST(TriangleMesh, SamplePointsUniformly) { auto mesh_empty = geometry::TriangleMesh(); EXPECT_THROW(mesh_empty.SamplePointsUniformly(100), std::runtime_error); - thrust::host_vector vertices; + std::vector vertices; vertices.push_back(Vector3f(0, 0, 0)); vertices.push_back(Vector3f(1, 0, 0)); vertices.push_back(Vector3f(0, 1, 0)); - thrust::host_vector triangles; + std::vector triangles; triangles.push_back(Vector3i(0, 1, 2)); auto mesh_simple = geometry::TriangleMesh(); @@ -702,11 +702,11 @@ TEST(TriangleMesh, SamplePointsUniformly) { EXPECT_TRUE(pcd_simple->colors_.size() == 0); EXPECT_TRUE(pcd_simple->normals_.size() == 0); - thrust::host_vector colors; + std::vector colors; colors.push_back(Vector3f(1, 0, 0)); colors.push_back(Vector3f(1, 0, 0)); colors.push_back(Vector3f(1, 0, 0)); - thrust::host_vector normals; + std::vector normals; normals.push_back(Vector3f(0, 1, 0)); normals.push_back(Vector3f(0, 1, 0)); normals.push_back(Vector3f(0, 1, 0)); @@ -717,8 +717,8 @@ TEST(TriangleMesh, SamplePointsUniformly) { EXPECT_TRUE(pcd_simple->colors_.size() == n_points); EXPECT_TRUE(pcd_simple->normals_.size() == n_points); - thrust::host_vector hc = pcd_simple->GetColors(); - thrust::host_vector hn = pcd_simple->GetNormals(); + std::vector hc = pcd_simple->GetColors(); + std::vector hn = pcd_simple->GetNormals(); for (size_t pidx = 0; pidx < n_points; ++pidx) { ExpectEQ(hc[pidx], Vector3f(1, 0, 0)); ExpectEQ(hn[pidx], Vector3f(0, 1, 0)); @@ -741,7 +741,7 @@ TEST(TriangleMesh, SamplePointsUniformly) { } // use triangle normal, this time the mesh has no vertex normals - mesh_simple.SetVertexNormals(thrust::host_vector()); + mesh_simple.SetVertexNormals(std::vector()); pcd_simple = mesh_simple.SamplePointsUniformly(n_points, true); EXPECT_TRUE(pcd_simple->points_.size() == n_points); EXPECT_TRUE(pcd_simple->colors_.size() == n_points); @@ -757,8 +757,8 @@ TEST(TriangleMesh, SamplePointsUniformly) { TEST(TriangleMesh, FilterSharpen) { auto mesh = std::make_shared(); - thrust::host_vector vertices; - thrust::host_vector triangles; + std::vector vertices; + std::vector triangles; vertices.push_back({0, 0, 0}); vertices.push_back({1, 0, 0}); vertices.push_back({0, 1, 0}); @@ -772,7 +772,7 @@ TEST(TriangleMesh, FilterSharpen) { mesh->SetTriangles(triangles); mesh = mesh->FilterSharpen(1, 1); - thrust::host_vector ref1; + std::vector ref1; ref1.push_back({0, 0, 0}); ref1.push_back({4, 0, 0}); ref1.push_back({0, 4, 0}); @@ -781,7 +781,7 @@ TEST(TriangleMesh, FilterSharpen) { ExpectEQ(mesh->GetVertices(), ref1); mesh = mesh->FilterSharpen(9, 0.1); - thrust::host_vector ref2; + std::vector ref2; ref2.push_back({0, 0, 0}); ref2.push_back({42.417997, 0, 0}); ref2.push_back({0, 42.417997, 0}); @@ -792,8 +792,8 @@ TEST(TriangleMesh, FilterSharpen) { TEST(TriangleMesh, FilterSmoothSimple) { auto mesh = std::make_shared(); - thrust::host_vector vertices; - thrust::host_vector triangles; + std::vector vertices; + std::vector triangles; vertices.push_back({0, 0, 0}); vertices.push_back({1, 0, 0}); vertices.push_back({0, 1, 0}); @@ -807,7 +807,7 @@ TEST(TriangleMesh, FilterSmoothSimple) { mesh->SetTriangles(triangles); mesh = mesh->FilterSmoothSimple(1); - thrust::host_vector ref1; + std::vector ref1; ref1.push_back({0, 0, 0}); ref1.push_back({0.25, 0, 0}); ref1.push_back({0, 0.25, 0}); @@ -816,7 +816,7 @@ TEST(TriangleMesh, FilterSmoothSimple) { ExpectEQ(mesh->GetVertices(), ref1); mesh = mesh->FilterSmoothSimple(3); - thrust::host_vector ref2; + std::vector ref2; ref2.push_back({0, 0, 0}); ref2.push_back({0.003906, 0, 0}); ref2.push_back({0, 0.003906, 0}); @@ -827,13 +827,13 @@ TEST(TriangleMesh, FilterSmoothSimple) { TEST(TriangleMesh, FilterSmoothLaplacian) { auto mesh = std::make_shared(); - thrust::host_vector vertices; + std::vector vertices; vertices.push_back({0, 0, 0}); vertices.push_back({1, 0, 0}); vertices.push_back({0, 1, 0}); vertices.push_back({-1, 0, 0}); vertices.push_back({0, -1, 0}); - thrust::host_vector triangles; + std::vector triangles; triangles.push_back({0, 1, 2}); triangles.push_back({0, 2, 3}); triangles.push_back({0, 3, 4}); @@ -842,7 +842,7 @@ TEST(TriangleMesh, FilterSmoothLaplacian) { mesh->SetTriangles(triangles); mesh = mesh->FilterSmoothLaplacian(1, 0.5); - thrust::host_vector ref1; + std::vector ref1; ref1.push_back({0, 0, 0}); ref1.push_back({0.5, 0, 0}); ref1.push_back({0, 0.5, 0}); @@ -851,7 +851,7 @@ TEST(TriangleMesh, FilterSmoothLaplacian) { ExpectEQ(mesh->GetVertices(), ref1); mesh = mesh->FilterSmoothLaplacian(10, 0.5); - thrust::host_vector ref2; + std::vector ref2; ref2.push_back({0, 0, 0}); ref2.push_back({0.000488, 0, 0}); ref2.push_back({0, 0.000488, 0}); @@ -862,13 +862,13 @@ TEST(TriangleMesh, FilterSmoothLaplacian) { TEST(TriangleMesh, FilterSmoothTaubin) { auto mesh = std::make_shared(); - thrust::host_vector vertices; + std::vector vertices; vertices.push_back({0, 0, 0}); vertices.push_back({1, 0, 0}); vertices.push_back({0, 1, 0}); vertices.push_back({-1, 0, 0}); vertices.push_back({0, -1, 0}); - thrust::host_vector triangles; + std::vector triangles; triangles.push_back({0, 1, 2}); triangles.push_back({0, 2, 3}); triangles.push_back({0, 3, 4}); @@ -877,7 +877,7 @@ TEST(TriangleMesh, FilterSmoothTaubin) { mesh->SetTriangles(triangles); mesh = mesh->FilterSmoothTaubin(1, 0.5, -0.53); - thrust::host_vector ref1; + std::vector ref1; ref1.push_back({0, 0, 0}); ref1.push_back({0.765, 0, 0}); ref1.push_back({0, 0.765, 0}); @@ -886,7 +886,7 @@ TEST(TriangleMesh, FilterSmoothTaubin) { ExpectEQ(mesh->GetVertices(), ref1); mesh = mesh->FilterSmoothTaubin(10, 0.5, -0.53); - thrust::host_vector ref2; + std::vector ref2; ref2.push_back({0, 0, 0}); ref2.push_back({0.052514, 0, 0}); ref2.push_back({0, 0.052514, 0}); @@ -902,7 +902,7 @@ TEST(TriangleMesh, HasVertices) { EXPECT_FALSE(tm.HasVertices()); - thrust::host_vector vertices(size); + std::vector vertices(size); tm.SetVertices(vertices); EXPECT_TRUE(tm.HasVertices()); @@ -915,9 +915,9 @@ TEST(TriangleMesh, HasTriangles) { EXPECT_FALSE(tm.HasTriangles()); - thrust::host_vector vertices(size); + std::vector vertices(size); tm.SetVertices(vertices); - thrust::host_vector triangles(size); + std::vector triangles(size); tm.SetTriangles(triangles); EXPECT_TRUE(tm.HasTriangles()); @@ -930,9 +930,9 @@ TEST(TriangleMesh, HasVertexNormals) { EXPECT_FALSE(tm.HasVertexNormals()); - thrust::host_vector vertices(size); + std::vector vertices(size); tm.SetVertices(vertices); - thrust::host_vector vertex_normals(size); + std::vector vertex_normals(size); tm.SetVertexNormals(vertex_normals); EXPECT_TRUE(tm.HasVertexNormals()); @@ -945,9 +945,9 @@ TEST(TriangleMesh, HasVertexColors) { EXPECT_FALSE(tm.HasVertexColors()); - thrust::host_vector vertices(size); + std::vector vertices(size); tm.SetVertices(vertices); - thrust::host_vector vertex_colors(size); + std::vector vertex_colors(size); tm.SetVertexColors(vertex_colors); EXPECT_TRUE(tm.HasVertexColors()); @@ -960,11 +960,11 @@ TEST(TriangleMesh, HasTriangleNormals) { EXPECT_FALSE(tm.HasTriangleNormals()); - thrust::host_vector vertices(size); + std::vector vertices(size); tm.SetVertices(vertices); - thrust::host_vector triangles(size); + std::vector triangles(size); tm.SetTriangles(triangles); - thrust::host_vector triangle_normals(size); + std::vector triangle_normals(size); tm.SetTriangleNormals(triangle_normals); EXPECT_TRUE(tm.HasTriangleNormals()); @@ -985,7 +985,7 @@ TEST(TriangleMesh, NormalizeNormals) { {0.175031, 0.720545, 0.670953}, {0.816905, 0.253392, 0.518130}, {0.377967, 0.767871, 0.517219}, {0.782281, 0.621223, 0.046017}, {0.314385, 0.671253, 0.671253}}; - thrust::host_vector ref_vertex_normals(25); + std::vector ref_vertex_normals(25); for (int i = 0; i < 25; ++i) ref_vertex_normals[i] = ref_vertex_normals_raw[i]; @@ -1003,7 +1003,7 @@ TEST(TriangleMesh, NormalizeNormals) { {0.616413, 0.573987, 0.539049}, {0.372896, 0.762489, 0.528733}, {0.669715, 0.451103, 0.589905}, {0.771164, 0.057123, 0.634068}, {0.620625, 0.620625, 0.479217}}; - thrust::host_vector ref_triangle_normals(25); + std::vector ref_triangle_normals(25); for (int i = 0; i < 25; ++i) ref_triangle_normals[i] = ref_triangle_normals_raw[i]; @@ -1014,8 +1014,8 @@ TEST(TriangleMesh, NormalizeNormals) { geometry::TriangleMesh tm; - thrust::host_vector vertex_normals(size); - thrust::host_vector triangle_normals(size); + std::vector vertex_normals(size); + std::vector triangle_normals(size); Rand(vertex_normals, dmin, dmax, 0); Rand(triangle_normals, dmin, dmax, 1); tm.SetVertexNormals(vertex_normals); @@ -1035,9 +1035,9 @@ TEST(TriangleMesh, PaintUniformColor) { geometry::TriangleMesh tm; - thrust::host_vector vertices(size); + std::vector vertices(size); tm.SetVertices(vertices); - thrust::host_vector vertex_colors(size); + std::vector vertex_colors(size); tm.SetVertexColors(vertex_colors); Vector3f color(233. / 255., 171. / 255., 53.0 / 255.); @@ -1091,7 +1091,7 @@ TEST(TriangleMesh, CreateMeshSphere) { {-0.181636, -0.559017, -0.809017}, {0.181636, -0.559017, -0.809017}, {0.475528, -0.345492, -0.809017}}; - thrust::host_vector ref_vertices(42); + std::vector ref_vertices(42); for (int i = 0; i < 42; ++i) ref_vertices[i] = ref_vertices_raw[i]; Vector3i ref_triangles_raw[] = { @@ -1115,7 +1115,7 @@ TEST(TriangleMesh, CreateMeshSphere) { {36, 27, 26}, {36, 37, 27}, {37, 28, 27}, {37, 38, 28}, {38, 29, 28}, {38, 39, 29}, {39, 30, 29}, {39, 40, 30}, {40, 31, 30}, {40, 41, 31}, {41, 22, 31}, {41, 32, 22}}; - thrust::host_vector ref_triangles(80); + std::vector ref_triangles(80); for (int i = 0; i < 80; ++i) ref_triangles[i] = ref_triangles_raw[i]; auto output_tm = geometry::TriangleMesh::CreateSphere(1.0, 5); @@ -1152,7 +1152,7 @@ TEST(TriangleMesh, CreateMeshCylinder) { {-0.809017, 0.587785, -1.000000}, {-0.809017, -0.587785, -1.000000}, {0.309017, -0.951057, -1.000000}}; - thrust::host_vector ref_vertices(27); + std::vector ref_vertices(27); for (int i = 0; i < 27; ++i) ref_vertices[i] = ref_vertices_raw[i]; Vector3i ref_triangles_raw[] = { @@ -1169,7 +1169,7 @@ TEST(TriangleMesh, CreateMeshCylinder) { {22, 18, 17}, {22, 23, 18}, {23, 19, 18}, {23, 24, 19}, {24, 20, 19}, {24, 25, 20}, {25, 21, 20}, {25, 26, 21}, {26, 17, 21}, {26, 22, 17}}; - thrust::host_vector ref_triangles(50); + std::vector ref_triangles(50); for (int i = 0; i < 50; ++i) ref_triangles[i] = ref_triangles_raw[i]; auto output_tm = geometry::TriangleMesh::CreateCylinder(1.0, 2.0, 5); @@ -1184,13 +1184,13 @@ TEST(TriangleMesh, CreateMeshCone) { {1.000000, 0.000000, 0.000000}, {0.309017, 0.951057, 0.000000}, {-0.809017, 0.587785, 0.000000}, {-0.809017, -0.587785, 0.000000}, {0.309017, -0.951057, 0.000000}}; - thrust::host_vector ref_vertices(7); + std::vector ref_vertices(7); for (int i = 0; i < 7; ++i) ref_vertices[i] = ref_vertices_raw[i]; Vector3i ref_triangles_raw[] = {{0, 3, 2}, {1, 2, 3}, {0, 4, 3}, {1, 3, 4}, {0, 5, 4}, {1, 4, 5}, {0, 6, 5}, {1, 5, 6}, {0, 2, 6}, {1, 6, 2}}; - thrust::host_vector ref_triangles(10); + std::vector ref_triangles(10); for (int i = 0; i < 10; ++i) ref_triangles[i] = ref_triangles_raw[i]; auto output_tm = geometry::TriangleMesh::CreateCone(1.0, 2.0, 5); @@ -1218,7 +1218,7 @@ TEST(TriangleMesh, CreateMeshArrow) { {0.000000, 0.000000, 3.000000}, {1.500000, 0.000000, 2.000000}, {0.463525, 1.426585, 2.000000}, {-1.213525, 0.881678, 2.000000}, {-1.213525, -0.881678, 2.000000}, {0.463525, -1.426585, 2.000000}}; - thrust::host_vector ref_vertices(34); + std::vector ref_vertices(34); for (int i = 0; i < 34; ++i) ref_vertices[i] = ref_vertices_raw[i]; Vector3i ref_triangles_raw[] = { @@ -1237,7 +1237,7 @@ TEST(TriangleMesh, CreateMeshArrow) { {26, 17, 21}, {26, 22, 17}, {27, 30, 29}, {28, 29, 30}, {27, 31, 30}, {28, 30, 31}, {27, 32, 31}, {28, 31, 32}, {27, 33, 32}, {28, 32, 33}, {27, 29, 33}, {28, 33, 29}}; - thrust::host_vector ref_triangles(60); + std::vector ref_triangles(60); for (int i = 0; i < 60; ++i) ref_triangles[i] = ref_triangles_raw[i]; auto output_tm = geometry::TriangleMesh::CreateArrow(1.0, 1.5, 2.0, 1.0, 5); diff --git a/src/tests/knn/kdtree_flann.cpp b/src/tests/knn/kdtree_flann.cpp index 802cdffd..5f8cd612 100644 --- a/src/tests/knn/kdtree_flann.cpp +++ b/src/tests/knn/kdtree_flann.cpp @@ -45,13 +45,13 @@ struct is_inf_functor { } // namespace TEST(KDTreeFlann, SearchKNN) { - thrust::host_vector ref_indices; + std::vector ref_indices; int indices0[] = {27, 48, 4, 77, 90, 7, 54, 17, 76, 38, 39, 60, 15, 84, 11, 57, 3, 32, 99, 36, 52, 40, 26, 59, 22, 97, 20, 42, 73, 24}; for (int i = 0; i < 30; ++i) ref_indices.push_back(indices0[i]); - thrust::host_vector ref_distance2; + std::vector ref_distance2; float distances0[] = { 0.000000, 4.684353, 4.996539, 9.191849, 10.034604, 10.466745, 10.649751, 11.434066, 12.089195, 13.345638, 13.696270, 14.016148, @@ -67,7 +67,7 @@ TEST(KDTreeFlann, SearchKNN) { Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(10.0, 10.0, 10.0); - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); @@ -75,8 +75,8 @@ TEST(KDTreeFlann, SearchKNN) { Eigen::Vector3f query = {1.647059, 4.392157, 8.784314}; int knn = 30; - thrust::host_vector indices; - thrust::host_vector distance2; + std::vector indices; + std::vector distance2; int result = kdtree.SearchKNN(query, knn, indices, distance2); @@ -91,11 +91,11 @@ TEST(KDTreeFlann, SearchKNN) { } TEST(KDTreeFlann, SearchRadius) { - thrust::host_vector ref_indices; + std::vector ref_indices; int indices0[] = {27, 48, 4, 77, 90, 7, 54, 17, 76, 38, 39, 60, 15, 84, 11}; for (int i = 0; i < 15; ++i) ref_indices.push_back(indices0[i]); - thrust::host_vector ref_distance2; + std::vector ref_distance2; float distances0[] = {0.000000, 4.684353, 4.996539, 9.191849, 10.034604, 10.466745, 10.649751, 11.434066, 12.089195, 13.345638, 13.696270, 14.016148, @@ -109,7 +109,7 @@ TEST(KDTreeFlann, SearchRadius) { Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(10.0, 10.0, 10.0); - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); @@ -118,8 +118,8 @@ TEST(KDTreeFlann, SearchRadius) { Eigen::Vector3f query = {1.647059, 4.392157, 8.784314}; int max_nn = 15; float radius = 5.0; - thrust::host_vector indices; - thrust::host_vector distance2; + std::vector indices; + std::vector distance2; int result = kdtree.SearchRadius(query, radius, max_nn, indices, distance2); diff --git a/src/tests/knn/lbvh_knn.cpp b/src/tests/knn/lbvh_knn.cpp index d171ae48..a06960fc 100644 --- a/src/tests/knn/lbvh_knn.cpp +++ b/src/tests/knn/lbvh_knn.cpp @@ -45,13 +45,13 @@ struct is_inf_functor { } // namespace TEST(LinearBoundingVolumeHierarchyKNN, SearchKNN) { - thrust::host_vector ref_indices; + std::vector ref_indices; int indices0[] = {27, 48, 4, 77, 90, 7, 54, 17, 76, 38, 39, 60, 15, 84, 11, 57, 3, 32, 99, 36, 52, 40, 26, 59, 22, 97, 20, 42, 73, 24}; for (int i = 0; i < 30; ++i) ref_indices.push_back(indices0[i]); - thrust::host_vector ref_distance2; + std::vector ref_distance2; float distances0[] = { 0.000000, 4.684353, 4.996539, 9.191849, 10.034604, 10.466745, 10.649751, 11.434066, 12.089195, 13.345638, 13.696270, 14.016148, @@ -67,15 +67,15 @@ TEST(LinearBoundingVolumeHierarchyKNN, SearchKNN) { Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(10.0, 10.0, 10.0); - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); pc.SetPoints(points); knn::LinearBoundingVolumeHierarchyKNN kdtree(geometry::ConvertVector3fVectorRef(pc)); Eigen::Vector3f query = {1.647059, 4.392157, 8.784314}; - thrust::host_vector indices; - thrust::host_vector distance2; + std::vector indices; + std::vector distance2; int result = kdtree.SearchNN(query, std::numeric_limits::max(), indices, distance2); diff --git a/src/tests/odometry/odometry_tools.cpp b/src/tests/odometry/odometry_tools.cpp index 29014be0..0bd41cc8 100644 --- a/src/tests/odometry/odometry_tools.cpp +++ b/src/tests/odometry/odometry_tools.cpp @@ -20,8 +20,6 @@ **/ #include "tests/odometry/odometry_tools.h" -#include - using namespace cupoch; using namespace std; using namespace unit_test; @@ -38,7 +36,7 @@ shared_ptr odometry_tools::GenerateImage( image->Prepare(width, height, num_of_channels, bytes_per_channel); - thrust::host_vector data(image->data_.size()); + std::vector data(image->data_.size()); float* const depthData = Cast(&data[0]); Rand(depthData, width * height, vmin, vmax, seed); image->SetData(data); @@ -56,7 +54,7 @@ void odometry_tools::ShiftLeft(shared_ptr image, // int num_of_channels = image->num_of_channels_; // int bytes_per_channel = image->bytes_per_channel_; - thrust::host_vector data = image->GetData(); + std::vector data = image->GetData(); float* const float_data = Cast(&data[0]); for (int h = 0; h < height; h++) for (int w = 0; w < width; w++) @@ -75,7 +73,7 @@ void odometry_tools::ShiftUp(shared_ptr image, // int num_of_channels = image->num_of_channels_; // int bytes_per_channel = image->bytes_per_channel_; - thrust::host_vector data = image->GetData(); + std::vector data = image->GetData(); float* const float_data = Cast(&data[0]); for (int h = 0; h < height; h++) for (int w = 0; w < width; w++) @@ -99,7 +97,7 @@ shared_ptr odometry_tools::CorrespondenceMap(const int& width, image->Prepare(width, height, num_of_channels, bytes_per_channel); - thrust::host_vector data(image->data_.size()); + std::vector data(image->data_.size()); int* const int_data = Cast(&data[0]); size_t image_size = image->data_.size() / sizeof(int); Rand(int_data, image_size, vmin, vmax, seed); @@ -123,7 +121,7 @@ shared_ptr odometry_tools::DepthBuffer(const int& width, image->Prepare(width, height, num_of_channels, bytes_per_channel); - thrust::host_vector data(image->data_.size()); + std::vector data(image->data_.size()); float* const float_data = Cast(&data[0]); size_t image_size = image->data_.size() / sizeof(float); Rand(float_data, image_size, vmin, vmax, seed); diff --git a/src/tests/odometry/rgbdodometry_jacobian_from_color_term.cpp b/src/tests/odometry/rgbdodometry_jacobian_from_color_term.cpp index c6965b11..6588a562 100644 --- a/src/tests/odometry/rgbdodometry_jacobian_from_color_term.cpp +++ b/src/tests/odometry/rgbdodometry_jacobian_from_color_term.cpp @@ -29,7 +29,7 @@ using namespace cupoch; using namespace unit_test; TEST(RGBDOdometryJacobianFromColorTerm, ComputeJacobianAndResidual) { - thrust::host_vector ref_J_r(10); + std::vector ref_J_r(10); ref_J_r[0] << -1.208103, 0.621106, -0.040830, 0.173142, 0.260220, -1.164557; ref_J_r[1] << -0.338017, 0.140257, 0.019732, 0.030357, 0.128839, -0.395772; ref_J_r[2] << -0.235842, 0.122008, 0.029948, 0.037260, 0.119792, -0.194611; @@ -43,7 +43,7 @@ TEST(RGBDOdometryJacobianFromColorTerm, ComputeJacobianAndResidual) { float ref_r_raw[] = {0.419608, -0.360784, 0.274510, 0.564706, 0.835294, -0.352941, -0.545098, -0.360784, 0.121569, -0.094118}; - thrust::host_vector ref_r; + std::vector ref_r; for (int i = 0; i < 10; ++i) ref_r.push_back(ref_r_raw[i]); int width = 10; @@ -84,7 +84,7 @@ TEST(RGBDOdometryJacobianFromColorTerm, ComputeJacobianAndResidual) { extrinsic(2, 2) = 1.0; int rows = height; - thrust::host_vector corresps(rows); + std::vector corresps(rows); Rand(corresps, 0, 3, 0); odometry::RGBDOdometryJacobianFromColorTerm jacobian_method; diff --git a/src/tests/odometry/rgbdodometry_jacobian_from_hybrid_term.cpp b/src/tests/odometry/rgbdodometry_jacobian_from_hybrid_term.cpp index 3f4acbc2..ceb70dc2 100644 --- a/src/tests/odometry/rgbdodometry_jacobian_from_hybrid_term.cpp +++ b/src/tests/odometry/rgbdodometry_jacobian_from_hybrid_term.cpp @@ -29,7 +29,7 @@ using namespace cupoch; using namespace unit_test; TEST(RGBDOdometryJacobianFromHybridTerm, ComputeJacobianAndResidual) { - thrust::host_vector ref_J_r(20); + std::vector ref_J_r(20); ref_J_r[0] << -0.216112, 0.111107, -0.007304, 0.030973, 0.046549, -0.208322; ref_J_r[1] << -2.459541, 1.263714, -0.080521, 0.240151, 0.312196, -2.435808; ref_J_r[2] << -0.060466, 0.025090, 0.003530, 0.005430, 0.023047, -0.070798; @@ -62,7 +62,7 @@ TEST(RGBDOdometryJacobianFromHybridTerm, ComputeJacobianAndResidual) { -0.063136, 0.231499, -0.097510, 1.207652, -0.064539, 0.949145, 0.021747, 1.408284, -0.016836, 0.470714, }; - thrust::host_vector ref_r; + std::vector ref_r; for (int i = 0; i < 20; ++i) ref_r.push_back(ref_r_raw[i]); int width = 10; @@ -103,7 +103,7 @@ TEST(RGBDOdometryJacobianFromHybridTerm, ComputeJacobianAndResidual) { extrinsic(2, 2) = 1.0; int rows = height; - thrust::host_vector corresps(rows); + std::vector corresps(rows); Rand(corresps, 0, 3, 0); odometry::RGBDOdometryJacobianFromHybridTerm jacobian_method; diff --git a/src/tests/registration/feature.cpp b/src/tests/registration/feature.cpp index 1da3f126..7d596e2b 100644 --- a/src/tests/registration/feature.cpp +++ b/src/tests/registration/feature.cpp @@ -29,7 +29,7 @@ using namespace std; using namespace unit_test; TEST(Feature, ComputeFPFHFeature) { - thrust::host_vector points; + std::vector points; points.push_back(Vector3f(1.9765625, 2.58410227, 1.16015625)); points.push_back(Vector3f(1.9609375, 2.58455765, 1.16015625)); points.push_back(Vector3f(1.8984375, 2.58400571, 1.16015625)); @@ -51,7 +51,7 @@ TEST(Feature, ComputeFPFHFeature) { points.push_back(Vector3f(1.89438566, 2.59281059, 1.12763938)); points.push_back(Vector3f(1.84362796, 2.59052256, 1.12894744)); - thrust::host_vector normals; + std::vector normals; normals.push_back( Vector3f(-1.72579880e-02, -9.57760371e-01, -2.87049184e-01)); normals.push_back( @@ -145,7 +145,7 @@ TEST(Feature, ComputeFPFHFeature) { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; - thrust::host_vector::FeatureType> ref_features; + std::vector::FeatureType> ref_features; for (int i = 0; i < mat_features.cols(); i++) { ref_features.push_back(mat_features.col(i)); } diff --git a/src/tests/registration/kabsch.cpp b/src/tests/registration/kabsch.cpp index fb07b8a6..1a0bb2f7 100644 --- a/src/tests/registration/kabsch.cpp +++ b/src/tests/registration/kabsch.cpp @@ -36,7 +36,7 @@ TEST(Kabsch, Kabsch) { const size_t size = 20; Vector3f vmin(0.0, 0.0, 0.0); Vector3f vmax(1000.0, 1000.0, 1000.0); - thrust::host_vector points(size); + std::vector points(size); Rand(points, vmin, vmax, 0); geometry::PointCloud source; source.SetPoints(points); diff --git a/src/tests/test_utility/rand.cpp b/src/tests/test_utility/rand.cpp index 1eaba21f..d3b93f24 100644 --- a/src/tests/test_utility/rand.cpp +++ b/src/tests/test_utility/rand.cpp @@ -70,7 +70,7 @@ void unit_test::Rand(Vector3f &v, // Initialize an Vector2i vector. // Output range: [vmin:vmax]. // ---------------------------------------------------------------------------- -void unit_test::Rand(host_vector &v, +void unit_test::Rand(std::vector &v, const Vector2i &vmin, const Vector2i &vmax, const int &seed) { @@ -90,7 +90,7 @@ void unit_test::Rand(host_vector &v, // Initialize an Vector3i vector. // Output range: [vmin:vmax]. // ---------------------------------------------------------------------------- -void unit_test::Rand(host_vector &v, +void unit_test::Rand(std::vector &v, const Vector3i &vmin, const Vector3i &vmax, const int &seed) { @@ -112,7 +112,7 @@ void unit_test::Rand(host_vector &v, // Initialize an Vector3d vector. // Output range: [vmin:vmax]. // ---------------------------------------------------------------------------- -void unit_test::Rand(host_vector &v, +void unit_test::Rand(std::vector &v, const Vector3f &vmin, const Vector3f &vmax, const int &seed) { @@ -134,7 +134,7 @@ void unit_test::Rand(host_vector &v, // Initialize an Vector4i vector. // Output range: [vmin:vmax]. // ---------------------------------------------------------------------------- -void unit_test::Rand(host_vector &v, +void unit_test::Rand(std::vector &v, const int &vmin, const int &vmax, const int &seed) { @@ -154,7 +154,7 @@ void unit_test::Rand(host_vector &v, // Initialize an Vector4i vector. // Output range: [vmin:vmax]. // ---------------------------------------------------------------------------- -void unit_test::Rand(host_vector &v, +void unit_test::Rand(std::vector &v, const Vector4i &vmin, const Vector4i &vmax, const int &seed) { @@ -178,7 +178,7 @@ void unit_test::Rand(host_vector &v, // Initialize a uint8_t vector. // Output range: [vmin:vmax]. // ---------------------------------------------------------------------------- -void unit_test::Rand(host_vector &v, +void unit_test::Rand(std::vector &v, const uint8_t &vmin, const uint8_t &vmax, const int &seed) { @@ -211,7 +211,7 @@ void unit_test::Rand(int *const v, // Initialize an int vector. // Output range: [vmin:vmax]. // ---------------------------------------------------------------------------- -void unit_test::Rand(host_vector &v, +void unit_test::Rand(std::vector &v, const int &vmin, const int &vmax, const int &seed) { @@ -222,7 +222,7 @@ void unit_test::Rand(host_vector &v, // Initialize a size_t vector. // Output range: [vmin:vmax]. // ---------------------------------------------------------------------------- -void unit_test::Rand(host_vector &v, +void unit_test::Rand(std::vector &v, const size_t &vmin, const size_t &vmax, const int &seed) { @@ -254,7 +254,7 @@ void unit_test::Rand(float *const v, // Initialize a float vector. // Output range: [vmin:vmax]. // ---------------------------------------------------------------------------- -void unit_test::Rand(host_vector &v, +void unit_test::Rand(std::vector &v, const float &vmin, const float &vmax, const int &seed) { diff --git a/src/tests/test_utility/rand.h b/src/tests/test_utility/rand.h index c47c7195..74d7fe7d 100644 --- a/src/tests/test_utility/rand.h +++ b/src/tests/test_utility/rand.h @@ -20,7 +20,7 @@ **/ #pragma once -#include +#include #include @@ -43,42 +43,42 @@ void Rand(Eigen::Vector3f& v, // Initialize an Eigen::Vector2i vector. // Output range: [vmin:vmax]. -void Rand(thrust::host_vector& v, +void Rand(std::vector& v, const Eigen::Vector2i& vmin, const Eigen::Vector2i& vmax, const int& seed); // Initialize an Eigen::Vector3i vector. // Output range: [vmin:vmax]. -void Rand(thrust::host_vector& v, +void Rand(std::vector& v, const Eigen::Vector3i& vmin, const Eigen::Vector3i& vmax, const int& seed); // Initialize an Eigen::Vector3f vector. // Output range: [vmin:vmax]. -void Rand(thrust::host_vector& v, +void Rand(std::vector& v, const Eigen::Vector3f& vmin, const Eigen::Vector3f& vmax, const int& seed); // Initialize an Eigen::Vector4i vector. // Output range: [vmin:vmax]. -void Rand(thrust::host_vector& v, + void Rand(std::vector& v, const int& vmin, const int& vmax, const int& seed); // Initialize an Eigen::Vector4i vector. // Output range: [vmin:vmax]. -void Rand(thrust::host_vector& v, +void Rand(std::vector& v, const Eigen::Vector4i& vmin, const Eigen::Vector4i& vmax, const int& seed); // Initialize a uint8_t vector. // Output range: [vmin:vmax]. -void Rand(thrust::host_vector& v, +void Rand(std::vector& v, const uint8_t& vmin, const uint8_t& vmax, const int& seed); @@ -93,14 +93,14 @@ void Rand(int* const v, // Initialize an int vector. // Output range: [vmin:vmax]. -void Rand(thrust::host_vector& v, +void Rand(std::vector& v, const int& vmin, const int& vmax, const int& seed); // Initialize a size_t vector. // Output range: [vmin:vmax]. -void Rand(thrust::host_vector& v, +void Rand(std::vector& v, const size_t& vmin, const size_t& vmax, const int& seed); @@ -115,7 +115,7 @@ void Rand(float* const v, // Initialize a float vector. // Output range: [vmin:vmax]. -void Rand(thrust::host_vector& v, +void Rand(std::vector& v, const float& vmin, const float& vmax, const int& seed); diff --git a/src/tests/test_utility/sort.cpp b/src/tests/test_utility/sort.cpp index f3adfd79..cc11f44b 100644 --- a/src/tests/test_utility/sort.cpp +++ b/src/tests/test_utility/sort.cpp @@ -45,7 +45,7 @@ bool unit_test::sort::GE(const Eigen::Matrix& v0, // Sort a vector of Eigen::Matrix elements. // ---------------------------------------------------------------------------- template -void unit_test::sort::Do(host_vector>& v) { +void unit_test::sort::Do(std::vector>& v) { Eigen::Matrix temp = Eigen::Matrix::Zero(); for (size_t i = 0; i < v.size(); i++) { for (size_t j = 0; j < v.size(); j++) { @@ -62,5 +62,5 @@ template bool unit_test::sort::GE(const Eigen::Vector3f& v0, const Eigen::Vector3f& v1); template bool unit_test::sort::GE(const Eigen::Vector3i& v0, const Eigen::Vector3i& v1); -template void unit_test::sort::Do(host_vector& v); -template void unit_test::sort::Do(host_vector& v); \ No newline at end of file +template void unit_test::sort::Do(std::vector& v); +template void unit_test::sort::Do(std::vector& v); diff --git a/src/tests/test_utility/sort.h b/src/tests/test_utility/sort.h index e811b24b..c2b04e19 100644 --- a/src/tests/test_utility/sort.h +++ b/src/tests/test_utility/sort.h @@ -20,8 +20,6 @@ **/ #pragma once -#include - #include #include "cupoch/utility/eigen.h" @@ -36,6 +34,6 @@ bool GE(const Eigen::Matrix& v0, const Eigen::Matrix& v1); // method needed because std::sort failed on TravisCI/macOS (works fine on // Linux) template -void Do(thrust::host_vector>& v); +void Do(std::vector>& v); } // namespace sort } // namespace unit_test \ No newline at end of file diff --git a/src/tests/test_utility/unit_test.cpp b/src/tests/test_utility/unit_test.cpp index fb5efc43..b843d37e 100644 --- a/src/tests/test_utility/unit_test.cpp +++ b/src/tests/test_utility/unit_test.cpp @@ -53,8 +53,8 @@ void unit_test::ExpectEQ(const uint8_t* const v0, // ---------------------------------------------------------------------------- // Test equality of two vectors of uint8_t. // ---------------------------------------------------------------------------- -void unit_test::ExpectEQ(const host_vector& v0, - const host_vector& v1) { +void unit_test::ExpectEQ(const std::vector& v0, + const std::vector& v1) { EXPECT_EQ(v0.size(), v1.size()); ExpectEQ(v0.data(), v1.data(), v0.size()); } @@ -71,8 +71,8 @@ void unit_test::ExpectEQ(const int* const v0, // ---------------------------------------------------------------------------- // Test equality of two vectors of int. // ---------------------------------------------------------------------------- -void unit_test::ExpectEQ(const host_vector& v0, - const host_vector& v1) { +void unit_test::ExpectEQ(const std::vector& v0, + const std::vector& v1) { EXPECT_EQ(v0.size(), v1.size()); ExpectEQ(v0.data(), v1.data(), v0.size()); } @@ -89,8 +89,8 @@ void unit_test::ExpectEQ(const float* const v0, // ---------------------------------------------------------------------------- // Test equality of two vectors of float. // ---------------------------------------------------------------------------- -void unit_test::ExpectEQ(const host_vector& v0, - const host_vector& v1) { +void unit_test::ExpectEQ(const std::vector& v0, + const std::vector& v1) { EXPECT_EQ(v0.size(), v1.size()); ExpectEQ(v0.data(), v1.data(), v0.size()); } diff --git a/src/tests/test_utility/unit_test.h b/src/tests/test_utility/unit_test.h index 108d0cc4..43d185ce 100644 --- a/src/tests/test_utility/unit_test.h +++ b/src/tests/test_utility/unit_test.h @@ -27,7 +27,6 @@ #endif #include -#include #include @@ -58,8 +57,8 @@ void ExpectEQ(const Eigen::Matrix& v0, EXPECT_NEAR(v0.coeff(i), v1.coeff(i), threshold); } template -void ExpectEQ(const thrust::host_vector>& v0, - const thrust::host_vector>& v1, +void ExpectEQ(const std::vector>& v0, + const std::vector>& v1, double threshold = THRESHOLD_1E_4) { EXPECT_EQ(v0.size(), v1.size()); for (size_t i = 0; i < v0.size(); i++) ExpectEQ(v0[i], v1[i], threshold); @@ -86,12 +85,12 @@ void ExpectLE(const Eigen::Matrix& v0, } template void ExpectLE(const Eigen::Matrix& v0, - const thrust::host_vector>& v1) { + const std::vector>& v1) { for (size_t i = 0; i < v1.size(); i++) ExpectLE(v0, v1[i]); } template -void ExpectLE(const thrust::host_vector>& v0, - const thrust::host_vector>& v1) { +void ExpectLE(const std::vector>& v0, + const std::vector>& v1) { EXPECT_EQ(v0.size(), v1.size()); for (size_t i = 0; i < v0.size(); i++) ExpectLE(v0[i], v1[i]); } @@ -105,12 +104,12 @@ void ExpectGE(const Eigen::Matrix& v0, } template void ExpectGE(const Eigen::Matrix& v0, - const thrust::host_vector>& v1) { + const std::vector>& v1) { for (size_t i = 0; i < v1.size(); i++) ExpectGE(v0, v1[i]); } template -void ExpectGE(const thrust::host_vector>& v0, - const thrust::host_vector>& v1) { +void ExpectGE(const std::vector>& v0, + const std::vector>& v1) { EXPECT_EQ(v0.size(), v1.size()); for (size_t i = 0; i < v0.size(); i++) ExpectGE(v0[i], v1[i]); } @@ -121,22 +120,22 @@ void ExpectEQ(const uint8_t* const v0, const size_t& size); // Test equality of two vectors of uint8_t. -void ExpectEQ(const thrust::host_vector& v0, - const thrust::host_vector& v1); +void ExpectEQ(const std::vector& v0, + const std::vector& v1); // Test equality of two arrays of int. void ExpectEQ(const int* const v0, const int* const v1, const size_t& size); // Test equality of two vectors of int. -void ExpectEQ(const thrust::host_vector& v0, - const thrust::host_vector& v1); +void ExpectEQ(const std::vector& v0, + const std::vector& v1); // Test equality of two arrays of float. void ExpectEQ(const float* const v0, const float* const v1, const size_t& size); // Test equality of two vectors of float. -void ExpectEQ(const thrust::host_vector& v0, - const thrust::host_vector& v1); +void ExpectEQ(const std::vector& v0, + const std::vector& v1); // Test equality of two arrays of double. void ExpectEQ(const float* const v0, const float* const v1, const size_t& size);