Skip to content

Commit

Permalink
std vector interface
Browse files Browse the repository at this point in the history
  • Loading branch information
neka-nat committed Oct 5, 2024
1 parent daadbf9 commit cd43856
Show file tree
Hide file tree
Showing 54 changed files with 656 additions and 384 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
10 changes: 10 additions & 0 deletions src/cupoch/geometry/down_sample.cu
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,16 @@ std::shared_ptr<PointCloud> PointCloud::SelectByMask(
return output;
}

std::shared_ptr<PointCloud> PointCloud::SelectByIndex(
const std::vector<size_t> &indices, bool invert) const {
return SelectByIndex(utility::device_vector<size_t>(indices), invert);
}

std::shared_ptr<PointCloud> PointCloud::SelectByMask(
const std::vector<bool> &mask, bool invert) const {
return SelectByMask(utility::device_vector<bool>(mask), invert);
}

std::shared_ptr<PointCloud> PointCloud::VoxelDownSample(
float voxel_size) const {
auto output = std::make_shared<PointCloud>();
Expand Down
10 changes: 6 additions & 4 deletions src/cupoch/geometry/graph.cu
Original file line number Diff line number Diff line change
Expand Up @@ -177,8 +177,9 @@ Graph<Dim>::Graph(const Graph &other)
is_directed_(other.is_directed_) {}

template <int Dim>
thrust::host_vector<int> Graph<Dim>::GetEdgeIndexOffsets() const {
thrust::host_vector<int> edge_index_offsets = edge_index_offsets_;
std::vector<int> Graph<Dim>::GetEdgeIndexOffsets() const {
std::vector<int> edge_index_offsets;
copy_device_to_host(edge_index_offsets_, edge_index_offsets);
return edge_index_offsets;
}

Expand All @@ -189,8 +190,9 @@ void Graph<Dim>::SetEdgeIndexOffsets(
}

template <int Dim>
thrust::host_vector<float> Graph<Dim>::GetEdgeWeights() const {
thrust::host_vector<float> edge_weights = edge_weights_;
std::vector<float> Graph<Dim>::GetEdgeWeights() const {
std::vector<float> edge_weights;
copy_device_to_host(edge_weights_, edge_weights);
return edge_weights;
}

Expand Down
4 changes: 2 additions & 2 deletions src/cupoch/geometry/graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,10 +55,10 @@ class Graph : public LineSet<Dim> {
Graph(const Graph &other);
~Graph();

thrust::host_vector<int> GetEdgeIndexOffsets() const;
std::vector<int> GetEdgeIndexOffsets() const;
void SetEdgeIndexOffsets(
const thrust::host_vector<int> &edge_index_offsets);
thrust::host_vector<float> GetEdgeWeights() const;
std::vector<float> GetEdgeWeights() const;
void SetEdgeWeights(const thrust::host_vector<float> &edge_weights);

bool HasWeights() const {
Expand Down
17 changes: 15 additions & 2 deletions src/cupoch/geometry/image.cu
Original file line number Diff line number Diff line change
Expand Up @@ -389,13 +389,19 @@ Eigen::Vector2f Image::GetCenter() const {
return Eigen::Vector2f(width_ / 2, height_ / 2);
}

thrust::host_vector<uint8_t> Image::GetData() const {
thrust::host_vector<uint8_t> data = data_;
std::vector<uint8_t> Image::GetData() const {
std::vector<uint8_t> data(data_.size());
copy_device_to_host(data_, data);
return data;
}

void Image::SetData(const thrust::host_vector<uint8_t> &data) { data_ = data; }

void Image::SetData(const std::vector<uint8_t> &data) {
data_.resize(data.size());
copy_host_to_device(data, data_);
}

bool Image::TestImageBoundary(float u,
float v,
float inner_margin /* = 0.0 */) const {
Expand Down Expand Up @@ -519,6 +525,13 @@ std::shared_ptr<Image> Image::FilterHorizontal(
return output;
}

std::shared_ptr<Image> Image::FilterHorizontal(
const std::vector<float> &kernel) const {
utility::device_vector<float> d_kernel(kernel.size());
copy_host_to_device(kernel, d_kernel);
return FilterHorizontal(d_kernel);
}

std::shared_ptr<Image> Image::Filter(Image::FilterType type) const {
auto output = std::make_shared<Image>();
if (num_of_channels_ != 1 || bytes_per_channel_ != 4) {
Expand Down
6 changes: 5 additions & 1 deletion src/cupoch/geometry/image.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,9 @@ class Image : public GeometryBaseNoTrans2D {
Eigen::Vector2f GetMaxBound() const override;
Eigen::Vector2f GetCenter() const override;

thrust::host_vector<uint8_t> GetData() const;
std::vector<uint8_t> GetData() const;
void SetData(const thrust::host_vector<uint8_t> &data);
void SetData(const std::vector<uint8_t> &data);

/// \brief Test if coordinate `(u, v)` is located in the inner_marge of the
/// image.
Expand Down Expand Up @@ -171,6 +172,9 @@ class Image : public GeometryBaseNoTrans2D {
std::shared_ptr<Image> FilterHorizontal(
const utility::device_vector<float> &kernel) const;

std::shared_ptr<Image> FilterHorizontal(
const std::vector<float> &kernel) const;

std::shared_ptr<Image> BilateralFilter(int diameter,
float sigma_color,
float sigma_space) const;
Expand Down
13 changes: 9 additions & 4 deletions src/cupoch/geometry/laserscanbuffer.cu
Original file line number Diff line number Diff line change
Expand Up @@ -137,8 +137,8 @@ LaserScanBuffer::LaserScanBuffer(const LaserScanBuffer& other)
max_angle_(other.max_angle_),
origins_(other.origins_) {}

thrust::host_vector<float> LaserScanBuffer::GetRanges() const {
thrust::host_vector<float> ranges;
std::vector<float> LaserScanBuffer::GetRanges() const {
std::vector<float> ranges;
if (top_ == bottom_) {
return ranges;
}
Expand All @@ -161,8 +161,8 @@ thrust::host_vector<float> LaserScanBuffer::GetRanges() const {
}
}

thrust::host_vector<float> LaserScanBuffer::GetIntensities() const {
thrust::host_vector<float> intensities;
std::vector<float> LaserScanBuffer::GetIntensities() const {
std::vector<float> intensities;
if (top_ == bottom_) {
return intensities;
}
Expand Down Expand Up @@ -303,6 +303,11 @@ template LaserScanBuffer& LaserScanBuffer::AddRanges(
const Eigen::Matrix4f& transformation,
const thrust::host_vector<float>& intensities);

template LaserScanBuffer& LaserScanBuffer::AddRanges(
const std::vector<float>& ranges,
const Eigen::Matrix4f& transformation,
const std::vector<float>& intensities);


class ContainerLikePtr {
public:
Expand Down
4 changes: 2 additions & 2 deletions src/cupoch/geometry/laserscanbuffer.h
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@ class LaserScanBuffer : public GeometryBase3D {
~LaserScanBuffer();
LaserScanBuffer(const LaserScanBuffer &other);

thrust::host_vector<float> GetRanges() const;
thrust::host_vector<float> GetIntensities() const;
std::vector<float> GetRanges() const;
std::vector<float> GetIntensities() const;

LaserScanBuffer &Clear() override;
bool IsEmpty() const override;
Expand Down
26 changes: 26 additions & 0 deletions src/cupoch/geometry/lineset.cu
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,13 @@ LineSet<Dim>::LineSet(
points_(points),
lines_(lines) {}

template <int Dim>
LineSet<Dim>::LineSet(const std::vector<Eigen::Matrix<float, Dim, 1>> &points,
const std::vector<Eigen::Vector2i> &lines)
: GeometryBaseXD<Dim>(Geometry::GeometryType::LineSet),
points_(points),
lines_(lines) {}

template <int Dim>
LineSet<Dim>::LineSet(const std::vector<Eigen::Matrix<float, Dim, 1>> &path)
: GeometryBaseXD<Dim>(Geometry::GeometryType::LineSet) {
Expand Down Expand Up @@ -101,6 +108,13 @@ void LineSet<Dim>::SetPoints(
points_ = points;
}

template <int Dim>
void LineSet<Dim>::SetPoints(
const std::vector<Eigen::Matrix<float, Dim, 1>> &points) {
points_.resize(points.size());
copy_host_to_device(points, points_);
}

template <int Dim>
thrust::host_vector<Eigen::Matrix<float, Dim, 1>> LineSet<Dim>::GetPoints()
const {
Expand All @@ -113,6 +127,12 @@ void LineSet<Dim>::SetLines(const thrust::host_vector<Eigen::Vector2i> &lines) {
lines_ = lines;
}

template <int Dim>
void LineSet<Dim>::SetLines(const std::vector<Eigen::Vector2i> &lines) {
lines_.resize(lines.size());
copy_host_to_device(lines, lines_);
}

template <int Dim>
thrust::host_vector<Eigen::Vector2i> LineSet<Dim>::GetLines() const {
thrust::host_vector<Eigen::Vector2i> lines = lines_;
Expand All @@ -125,6 +145,12 @@ void LineSet<Dim>::SetColors(
colors_ = colors;
}

template <int Dim>
void LineSet<Dim>::SetColors(const std::vector<Eigen::Vector3f> &colors) {
colors_.resize(colors.size());
copy_host_to_device(colors, colors_);
}

template <int Dim>
thrust::host_vector<Eigen::Vector3f> LineSet<Dim>::GetColors() const {
thrust::host_vector<Eigen::Vector3f> colors = colors_;
Expand Down
6 changes: 6 additions & 0 deletions src/cupoch/geometry/lineset.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,18 +58,24 @@ class LineSet : public GeometryBaseXD<Dim> {
const utility::pinned_host_vector<Eigen::Vector2i> &lines);
LineSet(const thrust::host_vector<Eigen::Matrix<float, Dim, 1>> &points,
const thrust::host_vector<Eigen::Vector2i> &lines);
LineSet(const std::vector<Eigen::Matrix<float, Dim, 1>> &points,
const std::vector<Eigen::Vector2i> &lines);
LineSet(const std::vector<Eigen::Matrix<float, Dim, 1>> &path);
LineSet(const LineSet &other);
~LineSet();

void SetPoints(
const thrust::host_vector<Eigen::Matrix<float, Dim, 1>> &points);
void SetPoints(
const std::vector<Eigen::Matrix<float, Dim, 1>> &points);
thrust::host_vector<Eigen::Matrix<float, Dim, 1>> GetPoints() const;

void SetLines(const thrust::host_vector<Eigen::Vector2i> &lines);
void SetLines(const std::vector<Eigen::Vector2i> &lines);
thrust::host_vector<Eigen::Vector2i> GetLines() const;

void SetColors(const thrust::host_vector<Eigen::Vector3f> &colors);
void SetColors(const std::vector<Eigen::Vector3f> &colors);
thrust::host_vector<Eigen::Vector3f> GetColors() const;

public:
Expand Down
30 changes: 24 additions & 6 deletions src/cupoch/geometry/meshbase.cu
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,9 @@ MeshBase &MeshBase::operator=(const MeshBase &other) {
return *this;
}

thrust::host_vector<Eigen::Vector3f> MeshBase::GetVertices() const {
thrust::host_vector<Eigen::Vector3f> vertices = vertices_;
std::vector<Eigen::Vector3f> MeshBase::GetVertices() const {
std::vector<Eigen::Vector3f> vertices(vertices_.size());
copy_device_to_host(vertices_, vertices);
return vertices;
}

Expand All @@ -51,8 +52,14 @@ void MeshBase::SetVertices(
vertices_ = vertices;
}

thrust::host_vector<Eigen::Vector3f> MeshBase::GetVertexNormals() const {
thrust::host_vector<Eigen::Vector3f> vertex_normals = vertex_normals_;
void MeshBase::SetVertices(const std::vector<Eigen::Vector3f> &vertices) {
vertices_.resize(vertices.size());
copy_host_to_device(vertices, vertices_);
}

std::vector<Eigen::Vector3f> MeshBase::GetVertexNormals() const {
std::vector<Eigen::Vector3f> vertex_normals(vertex_normals_.size());
copy_device_to_host(vertex_normals_, vertex_normals);
return vertex_normals;
}

Expand All @@ -61,8 +68,14 @@ void MeshBase::SetVertexNormals(
vertex_normals_ = vertex_normals;
}

thrust::host_vector<Eigen::Vector3f> MeshBase::GetVertexColors() const {
thrust::host_vector<Eigen::Vector3f> vertex_colors = vertex_colors_;
void MeshBase::SetVertexNormals(const std::vector<Eigen::Vector3f> &vertex_normals) {
vertex_normals_.resize(vertex_normals.size());
copy_host_to_device(vertex_normals, vertex_normals_);
}

std::vector<Eigen::Vector3f> MeshBase::GetVertexColors() const {
std::vector<Eigen::Vector3f> vertex_colors(vertex_colors_.size());
copy_device_to_host(vertex_colors_, vertex_colors);
return vertex_colors;
}

Expand All @@ -71,6 +84,11 @@ void MeshBase::SetVertexColors(
vertex_colors_ = vertex_colors;
}

void MeshBase::SetVertexColors(const std::vector<Eigen::Vector3f> &vertex_colors) {
vertex_colors_.resize(vertex_colors.size());
copy_host_to_device(vertex_colors, vertex_colors_);
}

MeshBase &MeshBase::Clear() {
vertices_.clear();
vertex_normals_.clear();
Expand Down
10 changes: 6 additions & 4 deletions src/cupoch/geometry/meshbase.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,17 +59,19 @@ class MeshBase : public GeometryBase3D {
MeshBase(const MeshBase &other);
MeshBase &operator=(const MeshBase &other);

thrust::host_vector<Eigen::Vector3f> GetVertices() const;
std::vector<Eigen::Vector3f> GetVertices() const;
void SetVertices(const thrust::host_vector<Eigen::Vector3f> &vertices);
void SetVertices(const std::vector<Eigen::Vector3f> &vertices);

thrust::host_vector<Eigen::Vector3f> GetVertexNormals() const;
std::vector<Eigen::Vector3f> GetVertexNormals() const;
void SetVertexNormals(
const thrust::host_vector<Eigen::Vector3f> &vertex_normals);
void SetVertexNormals(const std::vector<Eigen::Vector3f> &vertex_normals);

thrust::host_vector<Eigen::Vector3f> GetVertexColors() const;
std::vector<Eigen::Vector3f> GetVertexColors() const;
void SetVertexColors(
const thrust::host_vector<Eigen::Vector3f> &vertex_colors);

void SetVertexColors(const std::vector<Eigen::Vector3f> &vertex_colors);
public:
virtual MeshBase &Clear() override;
virtual bool IsEmpty() const override;
Expand Down
8 changes: 8 additions & 0 deletions src/cupoch/geometry/occupancygrid.cu
Original file line number Diff line number Diff line change
Expand Up @@ -537,6 +537,14 @@ OccupancyGrid& OccupancyGrid::Insert(
return Insert(dev_points, viewpoint, max_range);
}

OccupancyGrid& OccupancyGrid::Insert(const std::vector<Eigen::Vector3f>& points,
const Eigen::Vector3f& viewpoint,
float max_range) {
utility::device_vector<Eigen::Vector3f> 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) {
Expand Down
3 changes: 3 additions & 0 deletions src/cupoch/geometry/occupancygrid.h
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,9 @@ class OccupancyGrid : public DenseGrid<OccupancyVoxel> {
const thrust::host_vector<Eigen::Vector3f>& points,
const Eigen::Vector3f& viewpoint,
float max_range = -1.0);
OccupancyGrid& Insert(const std::vector<Eigen::Vector3f>& points,
const Eigen::Vector3f& viewpoint,
float max_range = -1.0);
OccupancyGrid& Insert(const PointCloud& pointcloud,
const Eigen::Vector3f& viewpoint,
float max_range = -1.0);
Expand Down
Loading

0 comments on commit cd43856

Please sign in to comment.