diff --git a/perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp b/perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp index c1d84666f9a10..5ab26d75a0a41 100644 --- a/perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp +++ b/perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp @@ -56,10 +56,10 @@ namespace cuda inline void check_error(const ::cudaError_t e, const char * f, int n) { if (e != ::cudaSuccess) { - std::stringstream s; + ::std::stringstream s; s << ::cudaGetErrorName(e) << " (" << e << ")@" << f << "#L" << n << ": " << ::cudaGetErrorString(e); - throw std::runtime_error{s.str()}; + throw ::std::runtime_error{s.str()}; } } @@ -69,13 +69,13 @@ struct deleter }; template -using unique_ptr = std::unique_ptr; +using unique_ptr = ::std::unique_ptr; template -typename std::enable_if::value, cuda::unique_ptr>::type make_unique( - const std::size_t n) +typename ::std::enable_if<::std::is_array::value, cuda::unique_ptr>::type make_unique( + const ::std::size_t n) { - using U = typename std::remove_extent::type; + using U = typename ::std::remove_extent::type; U * p; CHECK_CUDA_ERROR(::cudaMalloc(reinterpret_cast(&p), sizeof(U) * n)); return cuda::unique_ptr{p}; @@ -107,7 +107,7 @@ inline T * get_next_ptr(size_t num_elem, void *& workspace, size_t & workspace_s { size_t size = get_size_aligned(num_elem); if (size > workspace_size) { - throw std::runtime_error("Workspace is too small!"); + throw ::std::runtime_error("Workspace is too small!"); } workspace_size -= size; T * ptr = reinterpret_cast(workspace); diff --git a/perception/tensorrt_yolo/lib/include/cuda_utils.hpp b/perception/tensorrt_yolo/lib/include/cuda_utils.hpp index a3b53a73720a1..8a8a21d99e2cb 100644 --- a/perception/tensorrt_yolo/lib/include/cuda_utils.hpp +++ b/perception/tensorrt_yolo/lib/include/cuda_utils.hpp @@ -57,10 +57,10 @@ namespace cuda void check_error(const ::cudaError_t e, const char * f, int n) { if (e != ::cudaSuccess) { - std::stringstream s; + ::std::stringstream s; s << ::cudaGetErrorName(e) << " (" << e << ")@" << f << "#L" << n << ": " << ::cudaGetErrorString(e); - throw std::runtime_error{s.str()}; + throw ::std::runtime_error{s.str()}; } } @@ -69,13 +69,13 @@ struct deleter void operator()(void * p) const { CHECK_CUDA_ERROR(::cudaFree(p)); } }; template -using unique_ptr = std::unique_ptr; +using unique_ptr = ::std::unique_ptr; template -typename std::enable_if::value, cuda::unique_ptr>::type make_unique( - const std::size_t n) +typename ::std::enable_if<::std::is_array::value, cuda::unique_ptr>::type make_unique( + const ::std::size_t n) { - using U = typename std::remove_extent::type; + using U = typename ::std::remove_extent::type; U * p; CHECK_CUDA_ERROR(::cudaMalloc(reinterpret_cast(&p), sizeof(U) * n)); return cuda::unique_ptr{p}; @@ -107,7 +107,7 @@ inline T * get_next_ptr(size_t num_elem, void *& workspace, size_t & workspace_s { size_t size = get_size_aligned(num_elem); if (size > workspace_size) { - throw std::runtime_error("Workspace is too small!"); + throw ::std::runtime_error("Workspace is too small!"); } workspace_size -= size; T * ptr = reinterpret_cast(workspace);