Skip to content

Commit f7a1c8d

Browse files
authored
Merge pull request #8959 from tier4/awsim-stable-patch-20240926
fix(trtexec_vendor, tensorrt_yolo): fix build error
2 parents 126be79 + ecd89f7 commit f7a1c8d

File tree

5 files changed

+14
-127
lines changed

5 files changed

+14
-127
lines changed

common/trtexec_vendor/CMakeLists.txt

-88
This file was deleted.

common/trtexec_vendor/env-hooks/trtexec_vendor.sh.in

-5
This file was deleted.

common/trtexec_vendor/package.xml

-20
This file was deleted.

perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -56,10 +56,10 @@ namespace cuda
5656
inline void check_error(const ::cudaError_t e, const char * f, int n)
5757
{
5858
if (e != ::cudaSuccess) {
59-
std::stringstream s;
59+
::std::stringstream s;
6060
s << ::cudaGetErrorName(e) << " (" << e << ")@" << f << "#L" << n << ": "
6161
<< ::cudaGetErrorString(e);
62-
throw std::runtime_error{s.str()};
62+
throw ::std::runtime_error{s.str()};
6363
}
6464
}
6565

@@ -69,13 +69,13 @@ struct deleter
6969
};
7070

7171
template <typename T>
72-
using unique_ptr = std::unique_ptr<T, deleter>;
72+
using unique_ptr = ::std::unique_ptr<T, deleter>;
7373

7474
template <typename T>
75-
typename std::enable_if<std::is_array<T>::value, cuda::unique_ptr<T>>::type make_unique(
76-
const std::size_t n)
75+
typename ::std::enable_if<::std::is_array<T>::value, cuda::unique_ptr<T>>::type make_unique(
76+
const ::std::size_t n)
7777
{
78-
using U = typename std::remove_extent<T>::type;
78+
using U = typename ::std::remove_extent<T>::type;
7979
U * p;
8080
CHECK_CUDA_ERROR(::cudaMalloc(reinterpret_cast<void **>(&p), sizeof(U) * n));
8181
return cuda::unique_ptr<T>{p};
@@ -107,7 +107,7 @@ inline T * get_next_ptr(size_t num_elem, void *& workspace, size_t & workspace_s
107107
{
108108
size_t size = get_size_aligned<T>(num_elem);
109109
if (size > workspace_size) {
110-
throw std::runtime_error("Workspace is too small!");
110+
throw ::std::runtime_error("Workspace is too small!");
111111
}
112112
workspace_size -= size;
113113
T * ptr = reinterpret_cast<T *>(workspace);

perception/tensorrt_yolo/lib/include/cuda_utils.hpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -57,10 +57,10 @@ namespace cuda
5757
void check_error(const ::cudaError_t e, const char * f, int n)
5858
{
5959
if (e != ::cudaSuccess) {
60-
std::stringstream s;
60+
::std::stringstream s;
6161
s << ::cudaGetErrorName(e) << " (" << e << ")@" << f << "#L" << n << ": "
6262
<< ::cudaGetErrorString(e);
63-
throw std::runtime_error{s.str()};
63+
throw ::std::runtime_error{s.str()};
6464
}
6565
}
6666

@@ -69,13 +69,13 @@ struct deleter
6969
void operator()(void * p) const { CHECK_CUDA_ERROR(::cudaFree(p)); }
7070
};
7171
template <typename T>
72-
using unique_ptr = std::unique_ptr<T, deleter>;
72+
using unique_ptr = ::std::unique_ptr<T, deleter>;
7373

7474
template <typename T>
75-
typename std::enable_if<std::is_array<T>::value, cuda::unique_ptr<T>>::type make_unique(
76-
const std::size_t n)
75+
typename ::std::enable_if<::std::is_array<T>::value, cuda::unique_ptr<T>>::type make_unique(
76+
const ::std::size_t n)
7777
{
78-
using U = typename std::remove_extent<T>::type;
78+
using U = typename ::std::remove_extent<T>::type;
7979
U * p;
8080
CHECK_CUDA_ERROR(::cudaMalloc(reinterpret_cast<void **>(&p), sizeof(U) * n));
8181
return cuda::unique_ptr<T>{p};
@@ -107,7 +107,7 @@ inline T * get_next_ptr(size_t num_elem, void *& workspace, size_t & workspace_s
107107
{
108108
size_t size = get_size_aligned<T>(num_elem);
109109
if (size > workspace_size) {
110-
throw std::runtime_error("Workspace is too small!");
110+
throw ::std::runtime_error("Workspace is too small!");
111111
}
112112
workspace_size -= size;
113113
T * ptr = reinterpret_cast<T *>(workspace);

0 commit comments

Comments
 (0)