cuda_utils.hpp 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120
  1. // Copyright 2020 TIER IV, Inc.
  2. //
  3. // Licensed under the Apache License, Version 2.0 (the "License");
  4. // you may not use this file except in compliance with the License.
  5. // You may obtain a copy of the License at
  6. //
  7. // http://www.apache.org/licenses/LICENSE-2.0
  8. //
  9. // Unless required by applicable law or agreed to in writing, software
  10. // distributed under the License is distributed on an "AS IS" BASIS,
  11. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  12. // See the License for the specific language governing permissions and
  13. // limitations under the License.
  14. /*
  15. * Copyright (c) 2020, NVIDIA CORPORATION. All rights reserved.
  16. *
  17. * Permission is hereby granted, free of charge, to any person obtaining a
  18. * copy of this software and associated documentation files (the "Software"),
  19. * to deal in the Software without restriction, including without limitation
  20. * the rights to use, copy, modify, merge, publish, distribute, sublicense,
  21. * and/or sell copies of the Software, and to permit persons to whom the
  22. * Software is furnished to do so, subject to the following conditions:
  23. *
  24. * The above copyright notice and this permission notice shall be included in
  25. * all copies or substantial portions of the Software.
  26. *
  27. * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
  28. * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
  29. * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
  30. * THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
  31. * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
  32. * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
  33. * DEALINGS IN THE SOFTWARE.
  34. */
  35. /*
  36. * This code is licensed under CC0 1.0 Universal (Public Domain).
  37. * You can use this without any limitation.
  38. * https://creativecommons.org/publicdomain/zero/1.0/deed.en
  39. */
  40. #ifndef LIDAR_CENTERPOINT__CUDA_UTILS_HPP_
  41. #define LIDAR_CENTERPOINT__CUDA_UTILS_HPP_
  42. #include <cuda_runtime_api.h>
  43. #include <memory>
  44. #include <sstream>
  45. #include <stdexcept>
  46. #include <type_traits>
  47. #define CHECK_CUDA_ERROR(e) (cuda::check_error(e, __FILE__, __LINE__))
  48. namespace cuda
  49. {
  50. inline void check_error(const ::cudaError_t e, const char * f, int n)
  51. {
  52. if (e != ::cudaSuccess) {
  53. std::stringstream s;
  54. s << ::cudaGetErrorName(e) << " (" << e << ")@" << f << "#L" << n << ": "
  55. << ::cudaGetErrorString(e);
  56. throw std::runtime_error{s.str()};
  57. }
  58. }
  59. struct deleter
  60. {
  61. void operator()(void * p) const { CHECK_CUDA_ERROR(::cudaFree(p)); }
  62. };
  63. template <typename T>
  64. using unique_ptr = std::unique_ptr<T, deleter>;
  65. template <typename T>
  66. typename std::enable_if<std::is_array<T>::value, cuda::unique_ptr<T>>::type make_unique(
  67. const std::size_t n)
  68. {
  69. using U = typename std::remove_extent<T>::type;
  70. U * p;
  71. CHECK_CUDA_ERROR(::cudaMalloc(reinterpret_cast<void **>(&p), sizeof(U) * n));
  72. return cuda::unique_ptr<T>{p};
  73. }
  74. template <typename T>
  75. cuda::unique_ptr<T> make_unique()
  76. {
  77. T * p;
  78. CHECK_CUDA_ERROR(::cudaMalloc(reinterpret_cast<void **>(&p), sizeof(T)));
  79. return cuda::unique_ptr<T>{p};
  80. }
  81. constexpr size_t CUDA_ALIGN = 256;
  82. template <typename T>
  83. inline size_t get_size_aligned(size_t num_elem)
  84. {
  85. size_t size = num_elem * sizeof(T);
  86. size_t extra_align = 0;
  87. if (size % CUDA_ALIGN != 0) {
  88. extra_align = CUDA_ALIGN - size % CUDA_ALIGN;
  89. }
  90. return size + extra_align;
  91. }
  92. template <typename T>
  93. inline T * get_next_ptr(size_t num_elem, void *& workspace, size_t & workspace_size)
  94. {
  95. size_t size = get_size_aligned<T>(num_elem);
  96. if (size > workspace_size) {
  97. throw std::runtime_error("Workspace is too small!");
  98. }
  99. workspace_size -= size;
  100. T * ptr = reinterpret_cast<T *>(workspace);
  101. workspace = reinterpret_cast<void *>(reinterpret_cast<uintptr_t>(workspace) + size);
  102. return ptr;
  103. }
  104. } // namespace cuda
  105. #endif // LIDAR_CENTERPOINT__CUDA_UTILS_HPP_