diff --git a/cpp/kiss_icp/core/VoxelHashMap.cpp b/cpp/kiss_icp/core/VoxelHashMap.cpp index 3497f2d4..96b04bc4 100644 --- a/cpp/kiss_icp/core/VoxelHashMap.cpp +++ b/cpp/kiss_icp/core/VoxelHashMap.cpp @@ -43,13 +43,14 @@ std::vector VoxelHashMap::Pointcloud() const { return points; } -void VoxelHashMap::Update(const Vector3dVector &points, const Eigen::Vector3d &origin) { +void VoxelHashMap::Update(const std::vector &points, + const Eigen::Vector3d &origin) { AddPoints(points); RemovePointsFarFromLocation(origin); } -void VoxelHashMap::Update(const Vector3dVector &points, const Sophus::SE3d &pose) { - Vector3dVector points_transformed(points.size()); +void VoxelHashMap::Update(const std::vector &points, const Sophus::SE3d &pose) { + std::vector points_transformed(points.size()); std::transform(points.cbegin(), points.cend(), points_transformed.begin(), [&](const auto &point) { return pose * point; }); const Eigen::Vector3d &origin = pose.translation(); diff --git a/cpp/kiss_icp/core/VoxelHashMap.hpp b/cpp/kiss_icp/core/VoxelHashMap.hpp index 782cf8ab..d307bf5d 100644 --- a/cpp/kiss_icp/core/VoxelHashMap.hpp +++ b/cpp/kiss_icp/core/VoxelHashMap.hpp @@ -34,7 +34,6 @@ namespace kiss_icp { struct VoxelHashMap { - using Vector3dVector = std::vector; using Voxel = Eigen::Vector3i; struct VoxelBlock { // buffer of points with a max limit of n_points